MERGE trunk -r463:494 -> branches/stable-1.1 (Version 1.1) stable-1.1
authorFlorian Pose <fp@igh-essen.com>
Thu, 03 Aug 2006 12:59:01 +0000
branchstable-1.1
changeset 1715 e675450f2174
parent 1714 f149465f4c63
child 1716 9440f4ff25c7
MERGE trunk -r463:494 -> branches/stable-1.1 (Version 1.1)
FEATURES
README
TODO
examples/mini/mini.c
examples/msr/msr_sample.c
examples/rtai/rtai_sample.c
include/ecdb.h
include/ecrt.h
master/Makefile
master/canopen.c
master/datagram.c
master/datagram.h
master/domain.c
master/domain.h
master/ethernet.c
master/ethernet.h
master/fsm.c
master/fsm.h
master/globals.h
master/mailbox.c
master/master.c
master/master.h
master/module.c
master/slave.c
master/slave.h
master/types.c
master/types.h
script/ec_list.pl
script/ethercat.sh
script/install.sh
script/lsec.pl
script/sysconfig
--- a/FEATURES	Thu Jul 13 13:10:57 2006 +0000
+++ b/FEATURES	Thu Aug 03 12:59:01 2006 +0000
@@ -38,7 +38,7 @@
     operation.
   - Controlling of slave states during realtime operation.
 
-* Free-Run mode, if master is idle.
+* Special Idle mode, when master is not in use.
   - Automatic scanning of slaves upon topology changes.
   - Bus visualisation and EoE processing without realtime process connected.
 
--- a/README	Thu Jul 13 13:10:57 2006 +0000
+++ b/README	Thu Aug 03 12:59:01 2006 +0000
@@ -60,8 +60,8 @@
 
 Realtime patches for the Linux kernel are supported, but not required. The
 realtime processing has to be done by the calling module (see API
-documentation). The EtherCAT master code itself is (except for the free-run
-mode) completely passive.
+documentation). The EtherCAT master code itself is completely passive (except
+for the idle mode).
 
 To avoid frame timeouts, deactivating DMA access for hard drives is
 recommented (hdparm -d0 <DEV>).
--- a/TODO	Thu Jul 13 13:10:57 2006 +0000
+++ b/TODO	Thu Aug 03 12:59:01 2006 +0000
@@ -8,12 +8,6 @@
 
 Important things to do:
 
-* New SDO-Configuration interface
-
-* Remove slave type information from master / New RT Interface
-
-* Always use state machines / remove simple IO code
-
 * SysFS interface
   - Add secondary slave address
   - Add SDO dictionary
--- a/examples/mini/mini.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/examples/mini/mini.c	Thu Aug 03 12:59:01 2006 +0000
@@ -42,8 +42,8 @@
 #include <linux/interrupt.h>
 
 #include "../../include/ecrt.h" // EtherCAT realtime interface
+#include "../../include/ecdb.h" // EtherCAT slave database
 
-#define ASYNC
 #define FREQUENCY 100
 
 /*****************************************************************************/
@@ -56,16 +56,14 @@
 spinlock_t master_lock = SPIN_LOCK_UNLOCKED;
 
 // data fields
-//void *r_ssi_input, *r_ssi_status, *r_4102[3];
-void *r_kbus_in, *r_kbus_out;
+void *r_ana_out;
 
 // channels
 uint32_t k_pos;
 uint8_t k_stat;
 
-ec_field_init_t domain1_fields[] = {
-    //{&r_kbus_out, "0", "Beckhoff", "BK1120", "Outputs", 0},
-    //{&r_kbus_in,  "0", "Beckhoff", "BK1120", "Inputs",  0},
+ec_pdo_reg_t domain1_pdos[] = {
+    {"1", Beckhoff_EL4132_Output1, &r_ana_out},
     {}
 };
 
@@ -74,31 +72,19 @@
 void run(unsigned long data)
 {
     static unsigned int counter = 0;
-    unsigned int i;
 
     spin_lock(&master_lock);
 
-#ifdef ASYNC
     // receive
-    ecrt_master_async_receive(master);
+    ecrt_master_receive(master);
     ecrt_domain_process(domain1);
-#else
-    // send and receive
-    ecrt_domain_queue(domain1);
-    ecrt_master_run(master);
-    ecrt_master_sync_io(master);
-    ecrt_domain_process(domain1);
-#endif
 
     // process data
     //k_pos = EC_READ_U32(r_ssi);
 
-#ifdef ASYNC
     // send
-    ecrt_domain_queue(domain1);
     ecrt_master_run(master);
-    ecrt_master_async_send(master);
-#endif
+    ecrt_master_send(master);
 
     spin_unlock(&master_lock);
 
@@ -107,9 +93,10 @@
     }
     else {
         counter = FREQUENCY;
-        printk(KERN_INFO "input = ");
-        for (i = 0; i < 22; i++) printk("%02X ", *((uint8_t *) r_kbus_in + i));
-        printk("\n");
+        //printk(KERN_INFO "input = ");
+        //for (i = 0; i < 22; i++)
+        //    printk("%02X ", *((uint8_t *) r_kbus_in + i));
+        //printk("\n");
     }
 
     // restart timer
@@ -136,8 +123,6 @@
 
 int __init init_mini_module(void)
 {
-    ec_slave_t *slave;
-
     printk(KERN_INFO "=== Starting Minimal EtherCAT environment... ===\n");
 
     if ((master = ecrt_request_master(0)) == NULL) {
@@ -154,69 +139,19 @@
         goto out_release_master;
     }
 
-    printk(KERN_INFO "Registering domain fields...\n");
-    if (ecrt_domain_register_field_list(domain1, domain1_fields)) {
-        printk(KERN_ERR "Field registration failed!\n");
+    printk(KERN_INFO "Registering PDOs...\n");
+    if (ecrt_domain_register_pdo_list(domain1, domain1_pdos)) {
+        printk(KERN_ERR "PDO registration failed!\n");
         goto out_release_master;
     }
 
-#if 1
-    printk(KERN_INFO "Setting variable data field sizes...\n");
-    if (!(slave = ecrt_master_get_slave(master, "0"))) {
-        printk(KERN_ERR "Failed to get slave!\n");
-        goto out_deactivate;
-    }
-    ecrt_slave_field_size(slave, "Outputs", 0, 0x16);
-    ecrt_slave_field_size(slave, "Inputs", 0, 0x16);
-#endif
-
     printk(KERN_INFO "Activating master...\n");
     if (ecrt_master_activate(master)) {
         printk(KERN_ERR "Failed to activate master!\n");
         goto out_release_master;
     }
 
-#if 1
-    if (ecrt_master_fetch_sdo_lists(master)) {
-        printk(KERN_ERR "Failed to fetch SDO lists!\n");
-        goto out_deactivate;
-    }
-    ecrt_master_print(master, 2);
-#else
-    ecrt_master_print(master, 0);
-#endif
-
-#if 0
-    if (!(slave = ecrt_master_get_slave(master, "5"))) {
-        printk(KERN_ERR "Failed to get slave 5!\n");
-        goto out_deactivate;
-    }
-
-    if (ecrt_slave_sdo_write_exp8(slave, 0x4061, 1,  0) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 2,  1) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 3,  1) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4066, 0,  0) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4067, 0,  4) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4068, 0,  0) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4069, 0, 25) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x406A, 0, 25) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x406B, 0, 50)) {
-        printk(KERN_ERR "Failed to configure SSI slave!\n");
-        goto out_deactivate;
-    }
-#endif
-
-#ifdef ASYNC
-    // send once and wait...
-    ecrt_master_prepare_async_io(master);
-#endif
-
-#if 1
-    if (ecrt_master_start_eoe(master)) {
-        printk(KERN_ERR "Failed to start EoE processing!\n");
-        goto out_deactivate;
-    }
-#endif
+    ecrt_master_prepare(master);
 
     printk("Starting cyclic sample thread.\n");
     init_timer(&timer);
@@ -227,10 +162,6 @@
     printk(KERN_INFO "=== Minimal EtherCAT environment started. ===\n");
     return 0;
 
-#if 1
- out_deactivate:
-    ecrt_master_deactivate(master);
-#endif
  out_release_master:
     ecrt_release_master(master);
  out_return:
--- a/examples/msr/msr_sample.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/examples/msr/msr_sample.c	Thu Aug 03 12:59:01 2006 +0000
@@ -48,8 +48,7 @@
 
 // EtherCAT
 #include "../../include/ecrt.h"
-
-#define ASYNC
+#include "../../include/ecdb.h"
 
 #define HZREDUCTION (MSR_ABTASTFREQUENZ / HZ)
 #define TIMERTICKS (1000000000 / MSR_ABTASTFREQUENZ)
@@ -66,16 +65,13 @@
 ec_domain_t *domain1 = NULL;
 
 // raw process data
-void *r_ssi;
-void *r_ssi_st;
+void *r_ana_out;
 
 // Channels
-uint32_t k_ssi;
-uint32_t k_ssi_st;
-
-ec_field_init_t domain1_fields[] = {
-    {&r_ssi,    "0:3", "Beckhoff", "EL5001", "InputValue", 0},
-    {&r_ssi_st, "0:3", "Beckhoff", "EL5001", "Status",     0},
+double k_ana_out;
+
+ec_pdo_reg_t domain1_pdos[] = {
+    {"3", Beckhoff_EL4132_Output1, &r_ana_out},
     {}
 };
 
@@ -85,28 +81,16 @@
 {
     rt_sem_wait(&master_sem);
 
-#ifdef ASYNC
-    // Empfangen
-    ecrt_master_async_receive(master);
+    // receive
+    ecrt_master_receive(master);
     ecrt_domain_process(domain1);
-#else
-    // Senden und empfangen
-    ecrt_domain_queue(domain1);
+
+    // Process data
+    EC_WRITE_S16(r_ana_out, k_ana_out / 10.0 * 0x7FFF);
+
+    // Send
     ecrt_master_run(master);
-    ecrt_master_sync_io(master);
-    ecrt_domain_process(domain1);
-#endif
-
-    // Prozessdaten verarbeiten
-    k_ssi    = EC_READ_U32(r_ssi);
-    k_ssi_st = EC_READ_U8 (r_ssi_st);
-
-#ifdef ASYNC
-    // Senden
-    ecrt_domain_queue(domain1);
-    ecrt_master_run(master);
-    ecrt_master_async_send(master);
-#endif
+    ecrt_master_send(master);
 
     rt_sem_signal(&master_sem);
 
@@ -128,8 +112,7 @@
 
 int msr_reg(void)
 {
-    msr_reg_kanal("/ssi_position", "", &k_ssi,    TUINT);
-    msr_reg_kanal("/ssi_status",   "", &k_ssi_st, TUINT);
+    msr_reg_kanal("/ana_out", "", &k_ana_out, TDBL);
     return 0;
 }
 
@@ -157,9 +140,6 @@
 int __init init_mod(void)
 {
     RTIME ticks;
-#if 0
-    ec_slave_t *slave;
-#endif
 
     printk(KERN_INFO "=== Starting EtherCAT RTAI MSR sample module... ===\n");
 
@@ -171,7 +151,7 @@
         goto out_return;
     }
 
-    if ((master = ecrt_request_master(0)) == NULL) {
+    if (!(master = ecrt_request_master(0))) {
         printk(KERN_ERR "Failed to request master 0!\n");
         goto out_msr_cleanup;
     }
@@ -184,9 +164,9 @@
         goto out_release_master;
     }
 
-    printk(KERN_INFO "Registering domain fields...\n");
-    if (ecrt_domain_register_field_list(domain1, domain1_fields)) {
-        printk(KERN_ERR "Failed to register domain fields.\n");
+    printk(KERN_INFO "Registering PDOs...\n");
+    if (ecrt_domain_register_pdo_list(domain1, domain1_pdos)) {
+        printk(KERN_ERR "Failed to register PDOs.\n");
         goto out_release_master;
     }
 
@@ -196,59 +176,7 @@
         goto out_release_master;
     }
 
-#if 0
-    if (ecrt_master_fetch_sdo_lists(master)) {
-        printk(KERN_ERR "Failed to fetch SDO lists!\n");
-        goto out_deactivate;
-    }
-    ecrt_master_print(master, 2);
-#else
-    ecrt_master_print(master, 0);
-#endif
-
-#if 0
-    if (!(slave = ecrt_master_get_slave(master, "0:3"))) {
-        printk(KERN_ERR "Failed to get slave!\n");
-        goto out_deactivate;
-    }
-
-    if (
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 1,  1) || // disable frame error bit
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 2,  0) || // power failure bit
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 3,  1) || // inhibit time
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 4,  0) || // test mode
-        ecrt_slave_sdo_write_exp8(slave, 0x4066, 0,  0) || // graycode
-        ecrt_slave_sdo_write_exp8(slave, 0x4067, 0,  5) || // 125kbaud
-        ecrt_slave_sdo_write_exp8(slave, 0x4068, 0,  0) || // single-turn
-        ecrt_slave_sdo_write_exp8(slave, 0x4069, 0, 25) || // frame size
-        ecrt_slave_sdo_write_exp8(slave, 0x406A, 0, 25) || // data length
-        ecrt_slave_sdo_write_exp16(slave, 0x406B, 0, 50) // inhibit time in us
-        ) {
-        printk(KERN_ERR "Failed to configure SSI slave!\n");
-        goto out_deactivate;
-    }
-#endif
-
-#if 0
-    if (!(slave = ecrt_master_get_slave(master, "1:0"))) {
-        printk(KERN_ERR "Failed to get slave!\n");
-        goto out_deactivate;
-    }
-    if (ecrt_slave_write_alias(slave, 0x5678)) {
-        printk(KERN_ERR "Failed to write alias!\n");
-        goto out_deactivate;
-    }
-#endif
-
-#ifdef ASYNC
-    // Einmal senden und warten...
-    ecrt_master_prepare_async_io(master);
-#endif
-
-    if (ecrt_master_start_eoe(master)) {
-        printk(KERN_ERR "Failed to start EoE processing!\n");
-        goto out_deactivate;
-    }
+    ecrt_master_prepare(master);
 
     printk("Starting cyclic sample thread...\n");
     ticks = start_rt_timer(nano2count(TIMERTICKS));
@@ -268,7 +196,6 @@
     rt_task_delete(&task);
  out_stop_timer:
     stop_rt_timer();
- out_deactivate:
     ecrt_master_deactivate(master);
  out_release_master:
     ecrt_release_master(master);
--- a/examples/rtai/rtai_sample.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/examples/rtai/rtai_sample.c	Thu Aug 03 12:59:01 2006 +0000
@@ -42,6 +42,7 @@
 
 // EtherCAT
 #include "../../include/ecrt.h"
+#include "../../include/ecdb.h"
 
 /*****************************************************************************/
 
@@ -51,12 +52,8 @@
 
 /*****************************************************************************/
 
-// comment this for synchronous IO
-#define ASYNC
-
 // RTAI task frequency in Hz
 #define FREQUENCY 10000
-
 #define TIMERTICKS (1000000000 / FREQUENCY)
 
 /*****************************************************************************/
@@ -64,22 +61,20 @@
 // RTAI
 RT_TASK task;
 SEM master_sem;
-cycles_t t_last_start = 0;
-cycles_t t_critical;
+cycles_t t_last_start = 0, t_critical;
 
 // EtherCAT
 ec_master_t *master = NULL;
 ec_domain_t *domain1 = NULL;
 
 // data fields
-void *r_ssi_input;
+void *r_ana_out;
 
 // channels
 uint32_t k_pos;
 
-ec_field_init_t domain1_fields[] = {
-    {&r_ssi_input, "3", "Beckhoff", "EL5001", "InputValue",   0},
-    {NULL,         "2", "Beckhoff", "EL4132", "OutputValue",  0},
+ec_pdo_reg_t domain1_pdos[] = {
+    {"2", Beckhoff_EL4132_Output1, &r_ana_out},
     {}
 };
 
@@ -92,27 +87,14 @@
         t_last_start = get_cycles();
         rt_sem_wait(&master_sem);
 
-#ifdef ASYNC
-        // receive
-        ecrt_master_async_receive(master);
+        ecrt_master_receive(master);
         ecrt_domain_process(domain1);
-#else
-        // send and receive
-        ecrt_domain_queue(domain1);
+
+        // process data
+        //k_pos = EC_READ_U32(r_ssi_input);
+
         ecrt_master_run(master);
-        ecrt_master_sync_io(master);
-        ecrt_domain_process(domain1);
-#endif
-
-        // process data
-        k_pos = EC_READ_U32(r_ssi_input);
-
-#ifdef ASYNC
-        // send
-        ecrt_domain_queue(domain1);
-        ecrt_master_run(master);
-        ecrt_master_async_send(master);
-#endif
+        ecrt_master_send(master);
 
         rt_sem_signal(&master_sem);
         rt_task_wait_period();
@@ -158,15 +140,14 @@
     ecrt_master_callbacks(master, request_lock, release_lock, NULL);
 
     printk(KERN_INFO "Registering domain...\n");
-    if (!(domain1 = ecrt_master_create_domain(master)))
-    {
+    if (!(domain1 = ecrt_master_create_domain(master))) {
         printk(KERN_ERR "Domain creation failed!\n");
         goto out_release_master;
     }
 
-    printk(KERN_INFO "Registering domain fields...\n");
-    if (ecrt_domain_register_field_list(domain1, domain1_fields)) {
-        printk(KERN_ERR "Field registration failed!\n");
+    printk(KERN_INFO "Registering PDOs...\n");
+    if (ecrt_domain_register_pdo_list(domain1, domain1_pdos)) {
+        printk(KERN_ERR "PDO registration failed!\n");
         goto out_release_master;
     }
 
@@ -176,53 +157,7 @@
         goto out_release_master;
     }
 
-#if 0
-    if (ecrt_master_fetch_sdo_lists(master)) {
-        printk(KERN_ERR "Failed to fetch SDO lists!\n");
-        goto out_deactivate;
-    }
-    ecrt_master_print(master, 2);
-#else
-    ecrt_master_print(master, 0);
-#endif
-
-#if 0
-    if (!(slave = ecrt_master_get_slave(master, "5"))) {
-        printk(KERN_ERR "Failed to get slave 5!\n");
-        goto out_deactivate;
-    }
-
-    if (ecrt_slave_sdo_write_exp8(slave, 0x4061, 1,  0) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 2,  1) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4061, 3,  1) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4066, 0,  0) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4067, 0,  4) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4068, 0,  0) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x4069, 0, 25) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x406A, 0, 25) ||
-        ecrt_slave_sdo_write_exp8(slave, 0x406B, 0, 50)) {
-        printk(KERN_ERR "Failed to configure SSI slave!\n");
-        goto out_deactivate;
-    }
-#endif
-
-#if 0
-    printk(KERN_INFO "Writing alias...\n");
-    if (ecrt_slave_sdo_write_exp16(slave, 0xBEEF)) {
-        printk(KERN_ERR "Failed to write alias!\n");
-        goto out_deactivate;
-    }
-#endif
-
-#ifdef ASYNC
-    // send once and wait...
-    ecrt_master_prepare_async_io(master);
-#endif
-
-    if (ecrt_master_start_eoe(master)) {
-        printk(KERN_ERR "Failed to start EoE processing!\n");
-        goto out_deactivate;
-    }
+    ecrt_master_prepare(master);
 
     printk("Starting cyclic sample thread...\n");
     requested_ticks = nano2count(TIMERTICKS);
@@ -248,7 +183,6 @@
     rt_task_delete(&task);
  out_stop_timer:
     stop_rt_timer();
- out_deactivate:
     ecrt_master_deactivate(master);
  out_release_master:
     ecrt_release_master(master);
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/include/ecdb.h	Thu Aug 03 12:59:01 2006 +0000
@@ -0,0 +1,51 @@
+/******************************************************************************
+ *
+ *  $Id$
+ *
+ *  Copyright (C) 2006  Florian Pose, Ingenieurgemeinschaft IgH
+ *
+ *  This file is part of the IgH EtherCAT Master.
+ *
+ *  The IgH EtherCAT Master is free software; you can redistribute it
+ *  and/or modify it under the terms of the GNU General Public License
+ *  as published by the Free Software Foundation; either version 2 of the
+ *  License, or (at your option) any later version.
+ *
+ *  The IgH EtherCAT Master 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.
+ *
+ *  You should have received a copy of the GNU General Public License
+ *  along with the IgH EtherCAT Master; if not, write to the Free Software
+ *  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+ *
+ *  The right to use EtherCAT Technology is granted and comes free of
+ *  charge under condition of compatibility of product made by
+ *  Licensee. People intending to distribute/sell products based on the
+ *  code, have to sign an agreement to guarantee that products using
+ *  software based on IgH EtherCAT master stay compatible with the actual
+ *  EtherCAT specification (which are released themselves as an open
+ *  standard) as the (only) precondition to have the right to use EtherCAT
+ *  Technology, IP and trade marks.
+ *
+ *****************************************************************************/
+
+/**
+   \file
+   EtherCAT Slave Database.
+*/
+
+/*****************************************************************************/
+
+#ifndef __ECDB_H__
+#define __ECDB_H__
+
+/*****************************************************************************/
+
+#define Beckhoff_EL4132_Output1 0x00000002, 0x10243052, 0x6411, 1
+#define Beckhoff_EL4132_Output2 0x00000002, 0x10243052, 0x6411, 2
+
+/*****************************************************************************/
+
+#endif
--- a/include/ecrt.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/include/ecrt.h	Thu Aug 03 12:59:01 2006 +0000
@@ -69,23 +69,22 @@
 typedef struct ec_slave ec_slave_t; /**< \see ec_slave */
 
 /**
-   Initialization type for field registrations.
-   This type is used as a parameter for the ec_domain_register_field_list()
+   Initialization type for PDO registrations.
+   This type is used as a parameter for the ec_domain_register_pdo_list()
    function.
 */
 
 typedef struct
 {
-    void **data_ptr; /**< address of the process data pointer */
     const char *slave_address; /**< slave address string (see
                                   ecrt_master_get_slave()) */
-    const char *vendor_name; /**< vendor name */
-    const char *product_name; /**< product name */
-    const char *field_name; /**< data field name */
-    unsigned int field_index; /**< index in data fields with same name */
-    unsigned int field_count; /**< number of data fields with same name */
+    uint32_t vendor_id; /**< vendor ID */
+    uint32_t product_code; /**< product code */
+    uint16_t pdo_index; /**< PDO index */
+    uint8_t pdo_subindex; /**< PDO subindex */
+    void **data_ptr; /**< address of the process data pointer */
 }
-ec_field_init_t;
+ec_pdo_reg_t;
 
 /******************************************************************************
  *  Master request functions
@@ -106,66 +105,47 @@
 int ecrt_master_activate(ec_master_t *master);
 void ecrt_master_deactivate(ec_master_t *master);
 
-int ecrt_master_fetch_sdo_lists(ec_master_t *master);
-
-void ecrt_master_sync_io(ec_master_t *master);
-void ecrt_master_async_send(ec_master_t *master);
-void ecrt_master_async_receive(ec_master_t *master);
-void ecrt_master_prepare_async_io(ec_master_t *master);
+void ecrt_master_prepare(ec_master_t *master);
+
+void ecrt_master_send(ec_master_t *master);
+void ecrt_master_receive(ec_master_t *master);
 
 void ecrt_master_run(ec_master_t *master);
 
-int ecrt_master_start_eoe(ec_master_t *master);
-
-void ecrt_master_debug(ec_master_t *master, int level);
-void ecrt_master_print(const ec_master_t *master, unsigned int verbosity);
-
 ec_slave_t *ecrt_master_get_slave(const ec_master_t *, const char *);
 
+int ecrt_master_state(const ec_master_t *master);
+
 /******************************************************************************
  *  Domain Methods
  *****************************************************************************/
 
-ec_slave_t *ecrt_domain_register_field(ec_domain_t *domain,
-                                       const char *address,
-                                       const char *vendor_name,
-                                       const char *product_name,
-                                       void **data_ptr, const char *field_name,
-                                       unsigned int field_index,
-                                       unsigned int field_count);
-int ecrt_domain_register_field_list(ec_domain_t *domain,
-                                    const ec_field_init_t *fields);
-
-void ecrt_domain_queue(ec_domain_t *domain);
+ec_slave_t *ecrt_domain_register_pdo(ec_domain_t *domain,
+                                     const char *address,
+                                     uint32_t vendor_id,
+                                     uint32_t product_code,
+                                     uint16_t pdo_index,
+                                     uint8_t pdo_subindex,
+                                     void **data_ptr);
+int ecrt_domain_register_pdo_list(ec_domain_t *domain,
+                                  const ec_pdo_reg_t *pdos);
+
 void ecrt_domain_process(ec_domain_t *domain);
-
-int ecrt_domain_state(ec_domain_t *domain);
+int ecrt_domain_state(const ec_domain_t *domain);
 
 /******************************************************************************
  *  Slave Methods
  *****************************************************************************/
 
-/* there SDO functions are deprecated! */
-
-int ecrt_slave_sdo_read_exp8(ec_slave_t *slave, uint16_t sdo_index,
-                              uint8_t sdo_subindex, uint8_t *value);
-int ecrt_slave_sdo_read_exp16(ec_slave_t *slave, uint16_t sdo_index,
-                              uint8_t sdo_subindex, uint16_t *value);
-int ecrt_slave_sdo_read_exp32(ec_slave_t *slave, uint16_t sdo_index,
-                              uint8_t sdo_subindex, uint32_t *value);
-int ecrt_slave_sdo_write_exp8(ec_slave_t *slave, uint16_t sdo_index,
-                              uint8_t sdo_subindex, uint8_t value);
-int ecrt_slave_sdo_write_exp16(ec_slave_t *slave, uint16_t sdo_index,
-                               uint8_t sdo_subindex, uint16_t value);
-int ecrt_slave_sdo_write_exp32(ec_slave_t *slave, uint16_t sdo_index,
-                               uint8_t sdo_subindex, uint32_t value);
-int ecrt_slave_sdo_read(ec_slave_t *slave, uint16_t sdo_index,
-                        uint8_t sdo_subindex, uint8_t *data, size_t *size);
-
-int ecrt_slave_write_alias(ec_slave_t *slave, uint16_t alias); // deprecated!
-
-int ecrt_slave_field_size(ec_slave_t *slave, const char *field_name,
-                          unsigned int field_index, size_t size);
+int ecrt_slave_conf_sdo8(ec_slave_t *slave, uint16_t sdo_index,
+                         uint8_t sdo_subindex, uint8_t value);
+int ecrt_slave_conf_sdo16(ec_slave_t *slave, uint16_t sdo_index,
+                          uint8_t sdo_subindex, uint16_t value);
+int ecrt_slave_conf_sdo32(ec_slave_t *slave, uint16_t sdo_index,
+                          uint8_t sdo_subindex, uint32_t value);
+
+int ecrt_slave_pdo_size(ec_slave_t *slave, uint16_t pdo_index,
+                        uint8_t pdo_subindex, size_t size);
 
 /******************************************************************************
  *  Bitwise read/write macros
--- a/master/Makefile	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/Makefile	Thu Aug 03 12:59:01 2006 +0000
@@ -42,8 +42,8 @@
 
 obj-m := ec_master.o
 
-ec_master-objs := module.o master.o device.o slave.o datagram.o types.o \
-		domain.o mailbox.o canopen.o ethernet.o debug.o fsm.o
+ec_master-objs := module.o master.o device.o slave.o datagram.o \
+		domain.o mailbox.o ethernet.o debug.o fsm.o
 
 REV := $(shell svnversion $(src) 2>/dev/null || echo "unknown")
 
--- a/master/canopen.c	Thu Jul 13 13:10:57 2006 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,726 +0,0 @@
-/******************************************************************************
- *
- *  $Id$
- *
- *  Copyright (C) 2006  Florian Pose, Ingenieurgemeinschaft IgH
- *
- *  This file is part of the IgH EtherCAT Master.
- *
- *  The IgH EtherCAT Master is free software; you can redistribute it
- *  and/or modify it under the terms of the GNU General Public License
- *  as published by the Free Software Foundation; either version 2 of the
- *  License, or (at your option) any later version.
- *
- *  The IgH EtherCAT Master 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.
- *
- *  You should have received a copy of the GNU General Public License
- *  along with the IgH EtherCAT Master; if not, write to the Free Software
- *  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
- *
- *  The right to use EtherCAT Technology is granted and comes free of
- *  charge under condition of compatibility of product made by
- *  Licensee. People intending to distribute/sell products based on the
- *  code, have to sign an agreement to guarantee that products using
- *  software based on IgH EtherCAT master stay compatible with the actual
- *  EtherCAT specification (which are released themselves as an open
- *  standard) as the (only) precondition to have the right to use EtherCAT
- *  Technology, IP and trade marks.
- *
- *****************************************************************************/
-
-/**
-   \file
-   Canopen-over-EtherCAT functions.
-*/
-
-/*****************************************************************************/
-
-#include <linux/delay.h>
-#include <linux/slab.h>
-#include <linux/module.h>
-
-#include "master.h"
-#include "mailbox.h"
-
-/*****************************************************************************/
-
-void ec_canopen_abort_msg(uint32_t);
-int ec_slave_fetch_sdo_descriptions(ec_slave_t *, ec_datagram_t *);
-int ec_slave_fetch_sdo_entries(ec_slave_t *, ec_datagram_t *,
-                               ec_sdo_t *, uint8_t);
-
-/*****************************************************************************/
-
-/**
-   Reads 32 bit of a CANopen SDO in expedited mode.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_sdo_read_exp(ec_slave_t *slave, /**< EtherCAT slave */
-                          uint16_t sdo_index, /**< SDO index */
-                          uint8_t sdo_subindex, /**< SDO subindex */
-                          uint8_t *target /**< 4-byte memory */
-                          )
-{
-    ec_datagram_t datagram;
-    size_t rec_size;
-    uint8_t *data;
-
-    ec_datagram_init(&datagram);
-
-    if (!(data = ec_slave_mbox_prepare_send(slave, &datagram, 0x03, 6)))
-        goto err;
-
-    EC_WRITE_U16(data, 0x2 << 12); // SDO request
-    EC_WRITE_U8 (data + 2, (0x1 << 1 // expedited transfer
-                            | 0x2 << 5)); // initiate upload request
-    EC_WRITE_U16(data + 3, sdo_index);
-    EC_WRITE_U8 (data + 5, sdo_subindex);
-
-    if (!(data = ec_slave_mbox_simple_io(slave, &datagram, &rec_size)))
-        goto err;
-
-    if (EC_READ_U16(data) >> 12 == 0x2 && // SDO request
-        EC_READ_U8 (data + 2) >> 5 == 0x4) { // abort SDO transfer request
-        EC_ERR("SDO upload 0x%04X:%X aborted on slave %i.\n",
-               sdo_index, sdo_subindex, slave->ring_position);
-        ec_canopen_abort_msg(EC_READ_U32(data + 6));
-        goto err;
-    }
-
-    if (EC_READ_U16(data) >> 12 != 0x3 || // SDO response
-        EC_READ_U8 (data + 2) >> 5 != 0x2 || // upload response
-        EC_READ_U16(data + 3) != sdo_index || // index
-        EC_READ_U8 (data + 5) != sdo_subindex) { // subindex
-        EC_ERR("SDO upload 0x%04X:%X failed:\n", sdo_index, sdo_subindex);
-        EC_ERR("Invalid SDO upload response at slave %i!\n",
-               slave->ring_position);
-        ec_print_data(data, rec_size);
-        goto err;
-    }
-
-    memcpy(target, data + 6, 4);
-
-    ec_datagram_clear(&datagram);
-    return 0;
- err:
-    ec_datagram_clear(&datagram);
-    return -1;
-}
-
-/*****************************************************************************/
-
-/**
-   Writes a CANopen SDO using expedited mode.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_sdo_write_exp(ec_slave_t *slave, /**< EtherCAT slave */
-                           uint16_t sdo_index, /**< SDO index */
-                           uint8_t sdo_subindex, /**< SDO subindex */
-                           const uint8_t *sdo_data, /**< new value */
-                           size_t size /**< Data size in bytes (1 - 4) */
-                           )
-{
-    uint8_t *data;
-    size_t rec_size;
-    ec_datagram_t datagram;
-
-    ec_datagram_init(&datagram);
-
-    if (size == 0 || size > 4) {
-        EC_ERR("Invalid data size!\n");
-        goto err;
-    }
-
-    if (!(data = ec_slave_mbox_prepare_send(slave, &datagram, 0x03, 0x0A)))
-        goto err;
-
-    EC_WRITE_U16(data, 0x2 << 12); // SDO request
-    EC_WRITE_U8 (data + 2, (0x1 // size specified
-                            | 0x1 << 1 // expedited transfer
-                            | (4 - size) << 2 // data set size
-                            | 0x1 << 5)); // initiate download request
-    EC_WRITE_U16(data + 3, sdo_index);
-    EC_WRITE_U8 (data + 5, sdo_subindex);
-    memcpy(data + 6, sdo_data, size);
-    if (size < 4) memset(data + 6 + size, 0x00, 4 - size);
-
-    if (!(data = ec_slave_mbox_simple_io(slave, &datagram, &rec_size)))
-        goto err;
-
-    if (EC_READ_U16(data) >> 12 == 0x2 && // SDO request
-        EC_READ_U8 (data + 2) >> 5 == 0x4) { // abort SDO transfer request
-        EC_ERR("SDO download 0x%04X:%X (%i bytes) aborted on slave %i.\n",
-               sdo_index, sdo_subindex, size, slave->ring_position);
-        ec_canopen_abort_msg(EC_READ_U32(data + 6));
-        return -1;
-    }
-
-    if (EC_READ_U16(data) >> 12 != 0x3 || // SDO response
-        EC_READ_U8 (data + 2) >> 5 != 0x3 || // download response
-        EC_READ_U16(data + 3) != sdo_index || // index
-        EC_READ_U8 (data + 5) != sdo_subindex) { // subindex
-        EC_ERR("SDO download 0x%04X:%X (%i bytes) failed:\n",
-               sdo_index, sdo_subindex, size);
-        EC_ERR("Invalid SDO download response at slave %i!\n",
-               slave->ring_position);
-        ec_print_data(data, rec_size);
-        return -1;
-    }
-
-    ec_datagram_clear(&datagram);
-    return 0;
- err:
-    ec_datagram_clear(&datagram);
-    return -1;
-}
-
-/*****************************************************************************/
-
-/**
-   Reads a CANopen SDO in normal mode.
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-   \todo Make size non-pointer.
-*/
-
-int ecrt_slave_sdo_read(ec_slave_t *slave, /**< EtherCAT slave */
-                        uint16_t sdo_index, /**< SDO index */
-                        uint8_t sdo_subindex, /**< SDO subindex */
-                        uint8_t *target, /**< memory for value */
-                        size_t *size /**< target memory size */
-                        )
-{
-    uint8_t *data;
-    size_t rec_size, data_size;
-    uint32_t complete_size;
-    ec_datagram_t datagram;
-
-    ec_datagram_init(&datagram);
-
-    if (!(data = ec_slave_mbox_prepare_send(slave, &datagram, 0x03, 6)))
-        goto err;
-
-    EC_WRITE_U16(data, 0x2 << 12); // SDO request
-    EC_WRITE_U8 (data + 2, 0x2 << 5); // initiate upload request
-    EC_WRITE_U16(data + 3, sdo_index);
-    EC_WRITE_U8 (data + 5, sdo_subindex);
-
-    if (!(data = ec_slave_mbox_simple_io(slave, &datagram, &rec_size)))
-        goto err;
-
-    if (EC_READ_U16(data) >> 12 == 0x2 && // SDO request
-        EC_READ_U8 (data + 2) >> 5 == 0x4) { // abort SDO transfer request
-        EC_ERR("SDO upload 0x%04X:%X aborted on slave %i.\n",
-               sdo_index, sdo_subindex, slave->ring_position);
-        ec_canopen_abort_msg(EC_READ_U32(data + 6));
-        goto err;
-    }
-
-    if (EC_READ_U16(data) >> 12 != 0x3 || // SDO response
-        EC_READ_U8 (data + 2) >> 5 != 0x2 || // initiate upload response
-        EC_READ_U16(data + 3) != sdo_index || // index
-        EC_READ_U8 (data + 5) != sdo_subindex) { // subindex
-        EC_ERR("SDO upload 0x%04X:%X failed:\n", sdo_index, sdo_subindex);
-        EC_ERR("Invalid SDO upload response at slave %i!\n",
-               slave->ring_position);
-        ec_print_data(data, rec_size);
-        goto err;
-    }
-
-    if (rec_size < 10) {
-        EC_ERR("Received currupted SDO upload response!\n");
-        ec_print_data(data, rec_size);
-        goto err;
-    }
-
-    if ((complete_size = EC_READ_U32(data + 6)) > *size) {
-        EC_ERR("SDO data does not fit into buffer (%i / %i)!\n",
-               complete_size, *size);
-        goto err;
-    }
-
-    data_size = rec_size - 10;
-
-    if (data_size != complete_size) {
-        EC_ERR("SDO data incomplete - Fragmenting not implemented.\n");
-        goto err;
-    }
-
-    memcpy(target, data + 10, data_size);
-
-    ec_datagram_clear(&datagram);
-    return 0;
- err:
-    ec_datagram_clear(&datagram);
-    return -1;
-}
-
-/*****************************************************************************/
-
-/**
-   Fetches the SDO dictionary of a slave.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_fetch_sdo_list(ec_slave_t *slave /**< EtherCAT slave */)
-{
-    uint8_t *data;
-    size_t rec_size;
-    unsigned int i, sdo_count;
-    ec_sdo_t *sdo;
-    uint16_t sdo_index;
-    ec_datagram_t datagram;
-
-    ec_datagram_init(&datagram);
-
-    if (!(data = ec_slave_mbox_prepare_send(slave, &datagram, 0x03, 8)))
-        goto err;
-
-    EC_WRITE_U16(data, 0x8 << 12); // SDO information
-    EC_WRITE_U8 (data + 2, 0x01); // Get OD List Request
-    EC_WRITE_U8 (data + 3, 0x00);
-    EC_WRITE_U16(data + 4, 0x0000);
-    EC_WRITE_U16(data + 6, 0x0001); // deliver all SDOs!
-
-    if (unlikely(ec_master_simple_io(slave->master, &datagram))) {
-        EC_ERR("Mailbox checking failed on slave %i!\n", slave->ring_position);
-        goto err;
-    }
-
-    do {
-        if (!(data = ec_slave_mbox_simple_receive(slave, &datagram,
-                                                  0x03, &rec_size)))
-            goto err;
-
-        if (EC_READ_U16(data) >> 12 == 0x8 && // SDO information
-            (EC_READ_U8(data + 2) & 0x7F) == 0x07) { // error response
-            EC_ERR("SDO information error response at slave %i!\n",
-                   slave->ring_position);
-            ec_canopen_abort_msg(EC_READ_U32(data + 6));
-            goto err;
-        }
-
-        if (EC_READ_U16(data) >> 12 != 0x8 || // SDO information
-            (EC_READ_U8 (data + 2) & 0x7F) != 0x02) { // Get OD List response
-            EC_ERR("Invalid SDO list response at slave %i!\n",
-                   slave->ring_position);
-            ec_print_data(data, rec_size);
-            goto err;
-        }
-
-        if (rec_size < 8) {
-            EC_ERR("Invalid data size!\n");
-            ec_print_data(data, rec_size);
-            goto err;
-        }
-
-        sdo_count = (rec_size - 8) / 2;
-        for (i = 0; i < sdo_count; i++) {
-            sdo_index = EC_READ_U16(data + 8 + i * 2);
-            if (!sdo_index) continue; // sometimes index is 0... ???
-
-            if (!(sdo = (ec_sdo_t *) kmalloc(sizeof(ec_sdo_t), GFP_KERNEL))) {
-                EC_ERR("Failed to allocate memory for SDO!\n");
-                goto err;
-            }
-
-            // Initialize SDO object
-            sdo->index = sdo_index;
-            //sdo->unkown = 0x0000;
-            sdo->object_code = 0x00;
-            sdo->name = NULL;
-            INIT_LIST_HEAD(&sdo->entries);
-
-            list_add_tail(&sdo->list, &slave->sdo_dictionary);
-        }
-    }
-    while (EC_READ_U8(data + 2) & 0x80);
-
-    // Fetch all SDO descriptions
-    if (ec_slave_fetch_sdo_descriptions(slave, &datagram)) goto err;
-
-    ec_datagram_clear(&datagram);
-    return 0;
- err:
-    ec_datagram_clear(&datagram);
-    return -1;
-}
-
-/*****************************************************************************/
-
-/**
-   Fetches the SDO descriptions for the known SDOs.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_fetch_sdo_descriptions(ec_slave_t *slave, /**< EtherCAT slave */
-                                    ec_datagram_t *datagram /**< datagram */
-                                    )
-{
-    uint8_t *data;
-    size_t rec_size, name_size;
-    ec_sdo_t *sdo;
-
-    list_for_each_entry(sdo, &slave->sdo_dictionary, list) {
-        if (!(data = ec_slave_mbox_prepare_send(slave, datagram, 0x03, 8)))
-            return -1;
-        EC_WRITE_U16(data, 0x8 << 12); // SDO information
-        EC_WRITE_U8 (data + 2, 0x03); // Get object description request
-        EC_WRITE_U8 (data + 3, 0x00);
-        EC_WRITE_U16(data + 4, 0x0000);
-        EC_WRITE_U16(data + 6, sdo->index); // SDO index
-
-        if (!(data = ec_slave_mbox_simple_io(slave, datagram, &rec_size)))
-            return -1;
-
-        if (EC_READ_U16(data) >> 12 == 0x8 && // SDO information
-            (EC_READ_U8 (data + 2) & 0x7F) == 0x07) { // error response
-            EC_ERR("SDO information error response at slave %i while"
-                   " fetching SDO 0x%04X!\n", slave->ring_position,
-                   sdo->index);
-            ec_canopen_abort_msg(EC_READ_U32(data + 6));
-            return -1;
-        }
-
-        if (EC_READ_U16(data) >> 12 != 0x8 || // SDO information
-            (EC_READ_U8 (data + 2) & 0x7F) != 0x04 || // Object desc. response
-            EC_READ_U16(data + 6) != sdo->index) { // SDO index
-            EC_ERR("Invalid object description response at slave %i while"
-                   " fetching SDO 0x%04X!\n", slave->ring_position,
-                   sdo->index);
-            ec_print_data(data, rec_size);
-            return -1;
-        }
-
-        if (rec_size < 12) {
-            EC_ERR("Invalid data size!\n");
-            ec_print_data(data, rec_size);
-            return -1;
-        }
-
-#if 0
-        EC_DBG("object desc response:\n");
-        ec_print_data(data, rec_size);
-#endif
-
-        //sdo->unknown = EC_READ_U16(data + 8);
-        sdo->object_code = EC_READ_U8(data + 11);
-
-        name_size = rec_size - 12;
-        if (name_size) {
-            if (!(sdo->name = kmalloc(name_size + 1, GFP_KERNEL))) {
-                EC_ERR("Failed to allocate SDO name!\n");
-                return -1;
-            }
-
-            memcpy(sdo->name, data + 12, name_size);
-            sdo->name[name_size] = 0;
-        }
-
-        if (EC_READ_U8(data + 2) & 0x80) {
-            EC_ERR("Fragment follows (not implemented)!\n");
-            return -1;
-        }
-
-        // Fetch all entries (subindices)
-        if (ec_slave_fetch_sdo_entries(slave, datagram, sdo,
-                                       EC_READ_U8(data + 10)))
-            return -1;
-    }
-
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Fetches all entries (subindices) to an SDO.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_fetch_sdo_entries(ec_slave_t *slave, /**< EtherCAT slave */
-                               ec_datagram_t *datagram, /**< datagram */
-                               ec_sdo_t *sdo, /**< SDO */
-                               uint8_t subindices /**< number of subindices */
-                               )
-{
-    uint8_t *data;
-    size_t rec_size, data_size;
-    uint8_t i;
-    ec_sdo_entry_t *entry;
-
-    for (i = 1; i <= subindices; i++) {
-        if (!(data = ec_slave_mbox_prepare_send(slave, datagram, 0x03, 10)))
-            return -1;
-
-        EC_WRITE_U16(data, 0x8 << 12); // SDO information
-        EC_WRITE_U8 (data + 2, 0x05); // Get entry description request
-        EC_WRITE_U8 (data + 3, 0x00);
-        EC_WRITE_U16(data + 4, 0x0000);
-        EC_WRITE_U16(data + 6, sdo->index); // SDO index
-        EC_WRITE_U8 (data + 8, i); // SDO subindex
-        EC_WRITE_U8 (data + 9, 0x00); // value info (no values)
-
-        if (!(data = ec_slave_mbox_simple_io(slave, datagram, &rec_size)))
-            return -1;
-
-        if (EC_READ_U16(data) >> 12 == 0x8 && // SDO information
-            (EC_READ_U8 (data + 2) & 0x7F) == 0x07) { // error response
-            EC_ERR("SDO information error response at slave %i while"
-                   " fetching SDO entry 0x%04X:%i!\n", slave->ring_position,
-                   sdo->index, i);
-            ec_canopen_abort_msg(EC_READ_U32(data + 6));
-            return -1;
-        }
-
-        if (EC_READ_U16(data) >> 12 != 0x8 || // SDO information
-            (EC_READ_U8(data + 2) & 0x7F) != 0x06 || // Entry desc. response
-            EC_READ_U16(data + 6) != sdo->index || // SDO index
-            EC_READ_U8(data + 8) != i) { // SDO subindex
-            EC_ERR("Invalid entry description response at slave %i while"
-                   " fetching SDO entry 0x%04X:%i!\n", slave->ring_position,
-                   sdo->index, i);
-            ec_print_data(data, rec_size);
-            return -1;
-        }
-
-        if (rec_size < 16) {
-            EC_ERR("Invalid data size!\n");
-            ec_print_data(data, rec_size);
-            return -1;
-        }
-
-        if (!EC_READ_U16(data + 12)) // bit length = 0
-            continue;
-
-        data_size = rec_size - 16;
-
-        if (!(entry = (ec_sdo_entry_t *)
-              kmalloc(sizeof(ec_sdo_entry_t) + data_size + 1, GFP_KERNEL))) {
-            EC_ERR("Failed to allocate entry!\n");
-            return -1;
-        }
-
-        entry->subindex = i;
-        entry->data_type = EC_READ_U16(data + 10);
-        entry->bit_length = EC_READ_U16(data + 12);
-
-        // memory for name string appended to entry
-        entry->name = (uint8_t *) entry + sizeof(ec_sdo_entry_t);
-
-        memcpy(entry->name, data + 16, data_size);
-        entry->name[data_size] = 0;
-
-        list_add_tail(&entry->list, &sdo->entries);
-    }
-
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   SDO abort messages.
-   The "abort SDO transfer request" supplies an abort code,
-   which can be translated to clear text. This table does
-   the mapping of the codes and messages.
-*/
-
-const ec_code_msg_t sdo_abort_messages[] = {
-    {0x05030000, "Toggle bit not changed"},
-    {0x05040000, "SDO protocol timeout"},
-    {0x05040001, "Client/Server command specifier not valid or unknown"},
-    {0x05040005, "Out of memory"},
-    {0x06010000, "Unsupported access to an object"},
-    {0x06010001, "Attempt to read a write-only object"},
-    {0x06010002, "Attempt to write a read-only object"},
-    {0x06020000, "This object does not exist in the object directory"},
-    {0x06040041, "The object cannot be mapped into the PDO"},
-    {0x06040042, "The number and length of the objects to be mapped would"
-     " exceed the PDO length"},
-    {0x06040043, "General parameter incompatibility reason"},
-    {0x06040047, "Gerneral internal incompatibility in device"},
-    {0x06060000, "Access failure due to a hardware error"},
-    {0x06070010, "Data type does not match, length of service parameter does"
-     " not match"},
-    {0x06070012, "Data type does not match, length of service parameter too"
-     " high"},
-    {0x06070013, "Data type does not match, length of service parameter too"
-     " low"},
-    {0x06090011, "Subindex does not exist"},
-    {0x06090030, "Value range of parameter exceeded"},
-    {0x06090031, "Value of parameter written too high"},
-    {0x06090032, "Value of parameter written too low"},
-    {0x06090036, "Maximum value is less than minimum value"},
-    {0x08000000, "General error"},
-    {0x08000020, "Data cannot be transferred or stored to the application"},
-    {0x08000021, "Data cannot be transferred or stored to the application"
-     " because of local control"},
-    {0x08000022, "Data cannot be transferred or stored to the application"
-     " because of the present device state"},
-    {0x08000023, "Object dictionary dynamic generation fails or no object"
-     " dictionary is present"},
-    {}
-};
-
-/*****************************************************************************/
-
-/**
-   Outputs an SDO abort message.
-*/
-
-void ec_canopen_abort_msg(uint32_t abort_code)
-{
-    const ec_code_msg_t *abort_msg;
-
-    for (abort_msg = sdo_abort_messages; abort_msg->code; abort_msg++) {
-        if (abort_msg->code == abort_code) {
-            EC_ERR("SDO abort message 0x%08X: \"%s\".\n",
-                   abort_msg->code, abort_msg->message);
-            return;
-        }
-    }
-
-    EC_ERR("Unknown SDO abort code 0x%08X.\n", abort_code);
-}
-
-/******************************************************************************
- *  Realtime interface
- *****************************************************************************/
-
-/**
-   Reads an 8-bit SDO in expedited mode.
-   See ec_slave_sdo_read_exp()
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_sdo_read_exp8(ec_slave_t *slave, /**< EtherCAT slave */
-                             uint16_t sdo_index, /**< SDO index */
-                             uint8_t sdo_subindex, /**< SDO subindex */
-                             uint8_t *target /**< memory for read value */
-                             )
-{
-    uint8_t data[4];
-    if (ec_slave_sdo_read_exp(slave, sdo_index, sdo_subindex, data)) return -1;
-    *target = EC_READ_U8(data);
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Reads a 16-bit SDO in expedited mode.
-   See ec_slave_sdo_read_exp()
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_sdo_read_exp16(ec_slave_t *slave, /**< EtherCAT slave */
-                              uint16_t sdo_index, /**< SDO index */
-                              uint8_t sdo_subindex, /**< SDO subindex */
-                              uint16_t *target /**< memory for read value */
-                              )
-{
-    uint8_t data[4];
-    if (ec_slave_sdo_read_exp(slave, sdo_index, sdo_subindex, data)) return -1;
-    *target = EC_READ_U16(data);
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Reads a 32-bit SDO in expedited mode.
-   See ec_slave_sdo_read_exp()
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_sdo_read_exp32(ec_slave_t *slave, /**< EtherCAT slave */
-                              uint16_t sdo_index, /**< SDO index */
-                              uint8_t sdo_subindex, /**< SDO subindex */
-                              uint32_t *target /**< memory for read value */
-                              )
-{
-    uint8_t data[4];
-    if (ec_slave_sdo_read_exp(slave, sdo_index, sdo_subindex, data)) return -1;
-    *target = EC_READ_U32(data);
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Writes an 8-bit SDO in expedited mode.
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_sdo_write_exp8(ec_slave_t *slave, /**< EtherCAT slave */
-                              uint16_t sdo_index, /**< SDO index */
-                              uint8_t sdo_subindex, /**< SDO subindex */
-                              uint8_t value /**< new value */
-                              )
-{
-    return ec_slave_sdo_write_exp(slave, sdo_index, sdo_subindex, &value, 1);
-}
-
-/*****************************************************************************/
-
-/**
-   Writes a 16-bit SDO in expedited mode.
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_sdo_write_exp16(ec_slave_t *slave, /**< EtherCAT slave */
-                               uint16_t sdo_index, /**< SDO index */
-                               uint8_t sdo_subindex, /**< SDO subindex */
-                               uint16_t value /**< new value */
-                               )
-{
-    uint8_t data[2];
-    EC_WRITE_U16(data, value);
-    return ec_slave_sdo_write_exp(slave, sdo_index, sdo_subindex, data, 2);
-}
-
-/*****************************************************************************/
-
-/**
-   Writes a 32-bit SDO in expedited mode.
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_sdo_write_exp32(ec_slave_t *slave, /**< EtherCAT slave */
-                               uint16_t sdo_index, /**< SDO index */
-                               uint8_t sdo_subindex, /**< SDO subindex */
-                               uint32_t value /**< new value */
-                               )
-{
-    uint8_t data[4];
-    EC_WRITE_U32(data, value);
-    return ec_slave_sdo_write_exp(slave, sdo_index, sdo_subindex, data, 4);
-}
-
-/*****************************************************************************/
-
-/** \cond */
-
-EXPORT_SYMBOL(ecrt_slave_sdo_read_exp8);
-EXPORT_SYMBOL(ecrt_slave_sdo_read_exp16);
-EXPORT_SYMBOL(ecrt_slave_sdo_read_exp32);
-EXPORT_SYMBOL(ecrt_slave_sdo_write_exp8);
-EXPORT_SYMBOL(ecrt_slave_sdo_write_exp16);
-EXPORT_SYMBOL(ecrt_slave_sdo_write_exp32);
-EXPORT_SYMBOL(ecrt_slave_sdo_read);
-
-/** \endcond */
-
-/*****************************************************************************/
--- a/master/datagram.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/datagram.c	Thu Aug 03 12:59:01 2006 +0000
@@ -52,7 +52,7 @@
         return -1; \
     datagram->index = 0; \
     datagram->working_counter = 0; \
-    datagram->state = EC_CMD_INIT;
+    datagram->state = EC_DATAGRAM_INIT;
 
 #define EC_FUNC_FOOTER \
     datagram->data_size = data_size; \
@@ -69,14 +69,14 @@
 
 void ec_datagram_init(ec_datagram_t *datagram /**< EtherCAT datagram */)
 {
-    datagram->type = EC_CMD_NONE;
+    datagram->type = EC_DATAGRAM_NONE;
     datagram->address.logical = 0x00000000;
     datagram->data = NULL;
     datagram->mem_size = 0;
     datagram->data_size = 0;
     datagram->index = 0x00;
     datagram->working_counter = 0x00;
-    datagram->state = EC_CMD_INIT;
+    datagram->state = EC_DATAGRAM_INIT;
     datagram->t_sent = 0;
 }
 
@@ -142,7 +142,7 @@
         EC_WARN("Using node address 0x0000!\n");
 
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_NPRD;
+    datagram->type = EC_DATAGRAM_NPRD;
     datagram->address.physical.slave = node_address;
     datagram->address.physical.mem = offset;
     EC_FUNC_FOOTER;
@@ -170,7 +170,7 @@
         EC_WARN("Using node address 0x0000!\n");
 
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_NPWR;
+    datagram->type = EC_DATAGRAM_NPWR;
     datagram->address.physical.slave = node_address;
     datagram->address.physical.mem = offset;
     EC_FUNC_FOOTER;
@@ -195,7 +195,7 @@
                      )
 {
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_APRD;
+    datagram->type = EC_DATAGRAM_APRD;
     datagram->address.physical.slave = (int16_t) ring_position * (-1);
     datagram->address.physical.mem = offset;
     EC_FUNC_FOOTER;
@@ -220,7 +220,7 @@
                      )
 {
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_APWR;
+    datagram->type = EC_DATAGRAM_APWR;
     datagram->address.physical.slave = (int16_t) ring_position * (-1);
     datagram->address.physical.mem = offset;
     EC_FUNC_FOOTER;
@@ -243,7 +243,7 @@
                     )
 {
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_BRD;
+    datagram->type = EC_DATAGRAM_BRD;
     datagram->address.physical.slave = 0x0000;
     datagram->address.physical.mem = offset;
     EC_FUNC_FOOTER;
@@ -266,7 +266,7 @@
                     )
 {
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_BWR;
+    datagram->type = EC_DATAGRAM_BWR;
     datagram->address.physical.slave = 0x0000;
     datagram->address.physical.mem = offset;
     EC_FUNC_FOOTER;
@@ -289,7 +289,7 @@
                     )
 {
     EC_FUNC_HEADER;
-    datagram->type = EC_CMD_LRW;
+    datagram->type = EC_DATAGRAM_LRW;
     datagram->address.logical = offset;
     EC_FUNC_FOOTER;
 }
--- a/master/datagram.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/datagram.h	Thu Aug 03 12:59:01 2006 +0000
@@ -55,14 +55,14 @@
 
 typedef enum
 {
-    EC_CMD_NONE = 0x00, /**< Dummy */
-    EC_CMD_APRD = 0x01, /**< Auto-increment physical read */
-    EC_CMD_APWR = 0x02, /**< Auto-increment physical write */
-    EC_CMD_NPRD = 0x04, /**< Node-addressed physical read */
-    EC_CMD_NPWR = 0x05, /**< Node-addressed physical write */
-    EC_CMD_BRD  = 0x07, /**< Broadcast read */
-    EC_CMD_BWR  = 0x08, /**< Broadcast write */
-    EC_CMD_LRW  = 0x0C  /**< Logical read/write */
+    EC_DATAGRAM_NONE = 0x00, /**< Dummy */
+    EC_DATAGRAM_APRD = 0x01, /**< Auto-increment physical read */
+    EC_DATAGRAM_APWR = 0x02, /**< Auto-increment physical write */
+    EC_DATAGRAM_NPRD = 0x04, /**< Node-addressed physical read */
+    EC_DATAGRAM_NPWR = 0x05, /**< Node-addressed physical write */
+    EC_DATAGRAM_BRD  = 0x07, /**< Broadcast read */
+    EC_DATAGRAM_BWR  = 0x08, /**< Broadcast write */
+    EC_DATAGRAM_LRW  = 0x0C  /**< Logical read/write */
 }
 ec_datagram_type_t;
 
@@ -72,12 +72,12 @@
 
 typedef enum
 {
-    EC_CMD_INIT, /**< new datagram */
-    EC_CMD_QUEUED, /**< datagram queued by master */
-    EC_CMD_SENT, /**< datagram has been sent */
-    EC_CMD_RECEIVED, /**< datagram has been received */
-    EC_CMD_TIMEOUT, /**< datagram timed out */
-    EC_CMD_ERROR /**< error while sending/receiving */
+    EC_DATAGRAM_INIT, /**< new datagram */
+    EC_DATAGRAM_QUEUED, /**< datagram queued by master */
+    EC_DATAGRAM_SENT, /**< datagram has been sent */
+    EC_DATAGRAM_RECEIVED, /**< datagram has been received */
+    EC_DATAGRAM_TIMED_OUT, /**< datagram timed out */
+    EC_DATAGRAM_ERROR /**< error while sending/receiving */
 }
 ec_datagram_state_t;
 
--- a/master/domain.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/domain.c	Thu Aug 03 12:59:01 2006 +0000
@@ -46,17 +46,33 @@
 
 /*****************************************************************************/
 
-void ec_domain_clear_field_regs(ec_domain_t *);
+/**
+   Data registration type.
+*/
+
+typedef struct
+{
+    struct list_head list; /**< list item */
+    ec_slave_t *slave; /**< slave */
+    const ec_sii_sync_t *sync; /**< sync manager */
+    off_t sync_offset; /**< pdo offset */
+    void **data_ptr; /**< pointer to process data pointer(s) */
+}
+ec_data_reg_t;
+
+/*****************************************************************************/
+
+void ec_domain_clear_data_regs(ec_domain_t *);
 ssize_t ec_show_domain_attribute(struct kobject *, struct attribute *, char *);
 
 /*****************************************************************************/
 
 /** \cond */
 
-EC_SYSFS_READ_ATTR(data_size);
+EC_SYSFS_READ_ATTR(image_size);
 
 static struct attribute *def_attrs[] = {
-    &attr_data_size,
+    &attr_image_size,
     NULL,
 };
 
@@ -91,7 +107,7 @@
     domain->base_address = 0;
     domain->response_count = 0xFFFFFFFF;
 
-    INIT_LIST_HEAD(&domain->field_regs);
+    INIT_LIST_HEAD(&domain->data_regs);
     INIT_LIST_HEAD(&domain->datagrams);
 
     // init kobject and add it to the hierarchy
@@ -127,7 +143,7 @@
         kfree(datagram);
     }
 
-    ec_domain_clear_field_regs(domain);
+    ec_domain_clear_data_regs(domain);
 
     kfree(domain);
 }
@@ -139,34 +155,70 @@
    \return 0 in case of success, else < 0
 */
 
-int ec_domain_reg_field(ec_domain_t *domain, /**< EtherCAT domain */
-                        ec_slave_t *slave, /**< slave */
-                        const ec_sync_t *sync, /**< sync manager */
-                        uint32_t field_offset, /**< data field offset */
-                        void **data_ptr /**< pointer to the process data
-                                           pointer */
-                        )
-{
-    ec_field_reg_t *field_reg;
-
-    if (!(field_reg =
-          (ec_field_reg_t *) kmalloc(sizeof(ec_field_reg_t), GFP_KERNEL))) {
-        EC_ERR("Failed to allocate field registration.\n");
+int ec_domain_reg_pdo_entry(ec_domain_t *domain, /**< EtherCAT domain */
+                            ec_slave_t *slave, /**< slave */
+                            const ec_sii_pdo_t *pdo,
+                            const ec_sii_pdo_entry_t *entry,
+                            /**< PDO registration entry */
+                            void **data_ptr /**< pointer to the process data
+                                               pointer */
+                            )
+{
+    ec_data_reg_t *data_reg;
+    const ec_sii_sync_t *sync;
+    const ec_sii_pdo_t *other_pdo;
+    const ec_sii_pdo_entry_t *other_entry;
+    unsigned int bit_offset, byte_offset, sync_found;
+
+    // Find sync manager for PDO
+    sync_found = 0;
+    list_for_each_entry(sync, &slave->sii_syncs, list) {
+        if (sync->index == pdo->sync_index) {
+            sync_found = 1;
+            break;
+        }
+    }
+
+    if (!sync_found) {
+        EC_ERR("No sync manager for PDO 0x%04X:%i.",
+               pdo->index, entry->subindex);
+        return -1;
+    }
+
+    // Calculate offset for process data pointer
+    bit_offset = 0;
+    byte_offset = 0;
+    list_for_each_entry(other_pdo, &slave->sii_pdos, list) {
+        if (other_pdo->sync_index != sync->index) continue;
+
+        list_for_each_entry(other_entry, &pdo->entries, list) {
+            if (other_entry == entry) {
+                byte_offset = bit_offset / 8;
+                break;
+            }
+            bit_offset += other_entry->bit_length;
+        }
+    }
+
+    // Allocate memory for data registration object
+    if (!(data_reg =
+          (ec_data_reg_t *) kmalloc(sizeof(ec_data_reg_t), GFP_KERNEL))) {
+        EC_ERR("Failed to allocate data registration.\n");
         return -1;
     }
 
     if (ec_slave_prepare_fmmu(slave, domain, sync)) {
         EC_ERR("FMMU configuration failed.\n");
-        kfree(field_reg);
+        kfree(data_reg);
         return -1;
     }
 
-    field_reg->slave = slave;
-    field_reg->sync = sync;
-    field_reg->field_offset = field_offset;
-    field_reg->data_ptr = data_ptr;
-
-    list_add_tail(&field_reg->list, &domain->field_regs);
+    data_reg->slave = slave;
+    data_reg->sync = sync;
+    data_reg->sync_offset = byte_offset;
+    data_reg->data_ptr = data_ptr;
+
+    list_add_tail(&data_reg->list, &domain->data_regs);
     return 0;
 }
 
@@ -176,13 +228,13 @@
    Clears the list of the registered data fields.
 */
 
-void ec_domain_clear_field_regs(ec_domain_t *domain /**< EtherCAT domain */)
-{
-    ec_field_reg_t *field_reg, *next;
-
-    list_for_each_entry_safe(field_reg, next, &domain->field_regs, list) {
-        list_del(&field_reg->list);
-        kfree(field_reg);
+void ec_domain_clear_data_regs(ec_domain_t *domain /**< EtherCAT domain */)
+{
+    ec_data_reg_t *data_reg, *next;
+
+    list_for_each_entry_safe(data_reg, next, &domain->data_regs, list) {
+        list_del(&data_reg->list);
+        kfree(data_reg);
     }
 }
 
@@ -222,7 +274,7 @@
    Creates a domain.
    Reserves domain memory, calculates the logical addresses of the
    corresponding FMMUs and sets the process data pointer of the registered
-   data fields.
+   process data.
    \return 0 in case of success, else < 0
 */
 
@@ -230,22 +282,22 @@
                     uint32_t base_address /**< logical base address */
                     )
 {
-    ec_field_reg_t *field_reg;
+    ec_data_reg_t *data_reg;
     ec_slave_t *slave;
     ec_fmmu_t *fmmu;
-    unsigned int i, j, cmd_count;
-    uint32_t field_off, field_off_cmd;
-    uint32_t cmd_offset;
-    size_t cmd_data_size, sync_size;
+    unsigned int i, j, datagram_count;
+    uint32_t pdo_off, pdo_off_datagram;
+    uint32_t datagram_offset;
+    size_t datagram_data_size, sync_size;
     ec_datagram_t *datagram;
 
     domain->base_address = base_address;
 
     // calculate size of process data and allocate memory
     domain->data_size = 0;
-    cmd_offset = base_address;
-    cmd_data_size = 0;
-    cmd_count = 0;
+    datagram_offset = base_address;
+    datagram_data_size = 0;
+    datagram_count = 0;
     list_for_each_entry(slave, &domain->master->slaves, list) {
         for (j = 0; j < slave->fmmu_count; j++) {
             fmmu = &slave->fmmus[j];
@@ -253,47 +305,48 @@
                 fmmu->logical_start_address = base_address + domain->data_size;
                 sync_size = ec_slave_calc_sync_size(slave, fmmu->sync);
                 domain->data_size += sync_size;
-                if (cmd_data_size + sync_size > EC_MAX_DATA_SIZE) {
-                    if (ec_domain_add_datagram(domain, cmd_offset,
-                                               cmd_data_size)) return -1;
-                    cmd_offset += cmd_data_size;
-                    cmd_data_size = 0;
-                    cmd_count++;
+                if (datagram_data_size + sync_size > EC_MAX_DATA_SIZE) {
+                    if (ec_domain_add_datagram(domain, datagram_offset,
+                                               datagram_data_size)) return -1;
+                    datagram_offset += datagram_data_size;
+                    datagram_data_size = 0;
+                    datagram_count++;
                 }
-                cmd_data_size += sync_size;
+                datagram_data_size += sync_size;
             }
         }
     }
 
     // allocate last datagram
-    if (cmd_data_size) {
-        if (ec_domain_add_datagram(domain, cmd_offset, cmd_data_size))
+    if (datagram_data_size) {
+        if (ec_domain_add_datagram(domain, datagram_offset,
+                                   datagram_data_size))
             return -1;
-        cmd_count++;
-    }
-
-    if (!cmd_count) {
+        datagram_count++;
+    }
+
+    if (!datagram_count) {
         EC_WARN("Domain %i contains no data!\n", domain->index);
-        ec_domain_clear_field_regs(domain);
+        ec_domain_clear_data_regs(domain);
         return 0;
     }
 
     // set all process data pointers
-    list_for_each_entry(field_reg, &domain->field_regs, list) {
-        for (i = 0; i < field_reg->slave->fmmu_count; i++) {
-            fmmu = &field_reg->slave->fmmus[i];
-            if (fmmu->domain == domain && fmmu->sync == field_reg->sync) {
-                field_off = fmmu->logical_start_address +
-                    field_reg->field_offset;
+    list_for_each_entry(data_reg, &domain->data_regs, list) {
+        for (i = 0; i < data_reg->slave->fmmu_count; i++) {
+            fmmu = &data_reg->slave->fmmus[i];
+            if (fmmu->domain == domain && fmmu->sync == data_reg->sync) {
+                pdo_off = fmmu->logical_start_address + data_reg->sync_offset;
                 // search datagram
                 list_for_each_entry(datagram, &domain->datagrams, list) {
-                    field_off_cmd = field_off - datagram->address.logical;
-                    if (field_off >= datagram->address.logical &&
-                        field_off_cmd < datagram->mem_size) {
-                        *field_reg->data_ptr = datagram->data + field_off_cmd;
+                    pdo_off_datagram = pdo_off - datagram->address.logical;
+                    if (pdo_off >= datagram->address.logical &&
+                        pdo_off_datagram < datagram->mem_size) {
+                        *data_reg->data_ptr = datagram->data +
+                            pdo_off_datagram;
                     }
                 }
-                if (!field_reg->data_ptr) {
+                if (!data_reg->data_ptr) {
                     EC_ERR("Failed to assign data pointer!\n");
                     return -1;
                 }
@@ -303,31 +356,26 @@
     }
 
     EC_INFO("Domain %i - Allocated %i bytes in %i datagram%s\n",
-            domain->index, domain->data_size, cmd_count,
-            cmd_count == 1 ? "" : "s");
-
-    ec_domain_clear_field_regs(domain);
-
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Sets the number of responding slaves and outputs it on demand.
-   This number isn't really the number of responding slaves, but the sum of
-   the working counters of all domain datagrams. Some slaves increase the
-   working counter by 2, some by 1.
-*/
-
-void ec_domain_response_count(ec_domain_t *domain, /**< EtherCAT domain */
-                              unsigned int count /**< new WC sum */
-                              )
-{
-    if (count != domain->response_count) {
-        domain->response_count = count;
-        EC_INFO("Domain %i working counter change: %i\n", domain->index,
-                count);
+            domain->index, domain->data_size, datagram_count,
+            datagram_count == 1 ? "" : "s");
+
+    ec_domain_clear_data_regs(domain);
+
+    return 0;
+}
+
+/*****************************************************************************/
+
+/**
+   Places all process data datagrams in the masters datagram queue.
+*/
+
+void ec_domain_queue(ec_domain_t *domain /**< EtherCAT domain */)
+{
+    ec_datagram_t *datagram;
+
+    list_for_each_entry(datagram, &domain->datagrams, list) {
+        ec_master_queue_datagram(domain->master, datagram);
     }
 }
 
@@ -345,7 +393,7 @@
 {
     ec_domain_t *domain = container_of(kobj, ec_domain_t, kobj);
 
-    if (attr == &attr_data_size) {
+    if (attr == &attr_image_size) {
         return sprintf(buffer, "%i\n", domain->data_size);
     }
 
@@ -357,62 +405,45 @@
  *****************************************************************************/
 
 /**
-   Registers a data field in a domain.
-   - If \a data_ptr is NULL, the slave is only checked against its type.
-   - If \a field_count is 0, it is assumed that one data field is to be
-   registered.
-   - If \a field_count is greater then 1, it is assumed that \a data_ptr
-   is an array of the respective size.
+   Registers a PDO in a domain.
+   - If \a data_ptr is NULL, the slave is only validated.
    \return pointer to the slave on success, else NULL
    \ingroup RealtimeInterface
 */
 
-ec_slave_t *ecrt_domain_register_field(ec_domain_t *domain,
-                                       /**< EtherCAT domain */
-                                       const char *address,
-                                       /**< ASCII address of the slave,
-                                          see ecrt_master_get_slave() */
-                                       const char *vendor_name,
-                                       /**< vendor name */
-                                       const char *product_name,
-                                       /**< product name */
-                                       void **data_ptr,
-                                       /**< address of the process data
-                                          pointer */
-                                       const char *field_name,
-                                       /**< data field name */
-                                       unsigned int field_index,
-                                       /**< offset of data fields with
-                                          \a field_type  */
-                                       unsigned int field_count
-                                       /**< number of data fields (with
-                                          the same type) to register */
-                                       )
+ec_slave_t *ecrt_domain_register_pdo(ec_domain_t *domain,
+                                     /**< EtherCAT domain */
+                                     const char *address,
+                                     /**< ASCII address of the slave,
+                                        see ecrt_master_get_slave() */
+                                     uint32_t vendor_id,
+                                     /**< vendor ID */
+                                     uint32_t product_code,
+                                     /**< product code */
+                                     uint16_t pdo_index,
+                                     /**< PDO index */
+                                     uint8_t pdo_subindex,
+                                     /**< PDO subindex */
+                                     void **data_ptr
+                                     /**< address of the process data
+                                        pointer */
+                                     )
 {
     ec_slave_t *slave;
-    const ec_slave_type_t *type;
     ec_master_t *master;
-    const ec_sync_t *sync;
-    const ec_field_t *field;
-    unsigned int field_counter, i, j, orig_field_index, orig_field_count;
-    uint32_t field_offset;
+    const ec_sii_pdo_t *pdo;
+    const ec_sii_pdo_entry_t *entry;
 
     master = domain->master;
 
     // translate address
     if (!(slave = ecrt_master_get_slave(master, address))) return NULL;
 
-    if (!(type = slave->type)) {
-        EC_ERR("Slave \"%s\" (position %i) has unknown type!\n", address,
-               slave->ring_position);
-        return NULL;
-    }
-
-    if (strcmp(vendor_name, type->vendor_name) ||
-        strcmp(product_name, type->product_name)) {
-        EC_ERR("Invalid slave type at position %i - Requested: \"%s %s\","
-               " found: \"%s %s\".\n", slave->ring_position, vendor_name,
-               product_name, type->vendor_name, type->product_name);
+    if (vendor_id != slave->sii_vendor_id ||
+        product_code != slave->sii_product_code) {
+        EC_ERR("Invalid slave type at position %i - Requested: 0x%08X 0x%08X,"
+               " found: 0x%08X 0x%08X\".\n", slave->ring_position, vendor_id,
+               product_code, slave->sii_vendor_id, slave->sii_product_code);
         return NULL;
     }
 
@@ -421,32 +452,22 @@
         slave->registered = 1;
     }
 
-    if (!field_count) field_count = 1;
-    orig_field_index = field_index;
-    orig_field_count = field_count;
-
-    field_counter = 0;
-    for (i = 0; type->sync_managers[i]; i++) {
-        sync = type->sync_managers[i];
-        field_offset = 0;
-        for (j = 0; sync->fields[j]; j++) {
-            field = sync->fields[j];
-            if (!strcmp(field->name, field_name)) {
-                if (field_counter++ == field_index) {
-                    if (data_ptr)
-                        ec_domain_reg_field(domain, slave, sync, field_offset,
-                                            data_ptr++);
-                    if (!(--field_count)) return slave;
-                    field_index++;
-                }
+    list_for_each_entry(pdo, &slave->sii_pdos, list) {
+        list_for_each_entry(entry, &pdo->entries, list) {
+            if (entry->index != pdo_index
+                || entry->subindex != pdo_subindex) continue;
+
+            if (data_ptr) {
+                ec_domain_reg_pdo_entry(domain, slave, pdo, entry, data_ptr);
             }
-            field_offset += field->size;
+
+            return slave;
         }
     }
 
-    EC_ERR("Slave %i (\"%s %s\") registration mismatch: Field \"%s\","
-           " index %i, count %i.\n", slave->ring_position, vendor_name,
-           product_name, field_name, orig_field_index, orig_field_count);
+    EC_ERR("Slave %i does not provide PDO 0x%04X:%i.\n",
+           slave->ring_position, pdo_index, pdo_subindex);
+    slave->registered = 0;
     return NULL;
 }
 
@@ -459,20 +480,21 @@
    \ingroup RealtimeInterface
 */
 
-int ecrt_domain_register_field_list(ec_domain_t *domain,
-                                    /**< EtherCAT domain */
-                                    const ec_field_init_t *fields
-                                    /**< array of data field registrations */
-                                    )
-{
-    const ec_field_init_t *field;
-
-    for (field = fields; field->slave_address; field++)
-        if (!ecrt_domain_register_field(domain, field->slave_address,
-                                        field->vendor_name,
-                                        field->product_name, field->data_ptr,
-                                        field->field_name, field->field_index,
-                                        field->field_count))
+int ecrt_domain_register_pdo_list(ec_domain_t *domain,
+                                  /**< EtherCAT domain */
+                                  const ec_pdo_reg_t *pdos
+                                  /**< array of PDO registrations */
+                                  )
+{
+    const ec_pdo_reg_t *pdo;
+
+    for (pdo = pdos; pdo->slave_address; pdo++)
+        if (!ecrt_domain_register_pdo(domain, pdo->slave_address,
+                                      pdo->vendor_id,
+                                      pdo->product_code,
+                                      pdo->pdo_index,
+                                      pdo->pdo_subindex,
+                                      pdo->data_ptr))
             return -1;
 
     return 0;
@@ -481,23 +503,7 @@
 /*****************************************************************************/
 
 /**
-   Places all process data datagrams in the masters datagram queue.
-   \ingroup RealtimeInterface
-*/
-
-void ecrt_domain_queue(ec_domain_t *domain /**< EtherCAT domain */)
-{
-    ec_datagram_t *datagram;
-
-    list_for_each_entry(datagram, &domain->datagrams, list) {
-        ec_master_queue_datagram(domain->master, datagram);
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   Processes received process data.
+   Processes received process data and requeues the domain datagram(s).
    \ingroup RealtimeInterface
 */
 
@@ -507,14 +513,19 @@
     ec_datagram_t *datagram;
 
     working_counter_sum = 0;
-
     list_for_each_entry(datagram, &domain->datagrams, list) {
-        if (datagram->state == EC_CMD_RECEIVED) {
+        if (datagram->state == EC_DATAGRAM_RECEIVED) {
             working_counter_sum += datagram->working_counter;
         }
     }
 
-    ec_domain_response_count(domain, working_counter_sum);
+    if (working_counter_sum != domain->response_count) {
+        domain->response_count = working_counter_sum;
+        EC_INFO("Domain %i working counter change: %i\n", domain->index,
+                domain->response_count);
+    }
+
+    ec_domain_queue(domain);
 }
 
 /*****************************************************************************/
@@ -525,12 +536,12 @@
    \ingroup RealtimeInterface
 */
 
-int ecrt_domain_state(ec_domain_t *domain /**< EtherCAT domain */)
+int ecrt_domain_state(const ec_domain_t *domain /**< EtherCAT domain */)
 {
     ec_datagram_t *datagram;
 
     list_for_each_entry(datagram, &domain->datagrams, list) {
-        if (datagram->state != EC_CMD_RECEIVED) return -1;
+        if (datagram->state != EC_DATAGRAM_RECEIVED) return -1;
     }
 
     return 0;
@@ -540,9 +551,8 @@
 
 /** \cond */
 
-EXPORT_SYMBOL(ecrt_domain_register_field);
-EXPORT_SYMBOL(ecrt_domain_register_field_list);
-EXPORT_SYMBOL(ecrt_domain_queue);
+EXPORT_SYMBOL(ecrt_domain_register_pdo);
+EXPORT_SYMBOL(ecrt_domain_register_pdo_list);
 EXPORT_SYMBOL(ecrt_domain_process);
 EXPORT_SYMBOL(ecrt_domain_state);
 
--- a/master/domain.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/domain.h	Thu Aug 03 12:59:01 2006 +0000
@@ -45,24 +45,8 @@
 #include <linux/kobject.h>
 
 #include "globals.h"
-#include "slave.h"
 #include "datagram.h"
-
-/*****************************************************************************/
-
-/**
-   Data field registration type.
-*/
-
-typedef struct
-{
-    struct list_head list; /**< list item */
-    ec_slave_t *slave; /**< slave */
-    const ec_sync_t *sync; /**< sync manager */
-    uint32_t field_offset; /**< data field offset */
-    void **data_ptr; /**< pointer to process data pointer(s) */
-}
-ec_field_reg_t;
+#include "master.h"
 
 /*****************************************************************************/
 
@@ -82,7 +66,7 @@
     struct list_head datagrams; /**< process data datagrams */
     uint32_t base_address; /**< logical offset address of the process data */
     unsigned int response_count; /**< number of responding slaves */
-    struct list_head field_regs; /**< data field registrations */
+    struct list_head data_regs; /**< PDO data registrations */
 };
 
 /*****************************************************************************/
@@ -90,6 +74,7 @@
 int ec_domain_init(ec_domain_t *, ec_master_t *, unsigned int);
 void ec_domain_clear(struct kobject *);
 int ec_domain_alloc(ec_domain_t *, uint32_t);
+void ec_domain_queue(ec_domain_t *);
 
 /*****************************************************************************/
 
--- a/master/ethernet.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/ethernet.c	Thu Aug 03 12:59:01 2006 +0000
@@ -155,10 +155,8 @@
 
 void ec_eoe_clear(ec_eoe_t *eoe /**< EoE handler */)
 {
-    if (eoe->dev) {
-        unregister_netdev(eoe->dev);
-        free_netdev(eoe->dev);
-    }
+    unregister_netdev(eoe->dev);
+    free_netdev(eoe->dev);
 
     // empty transmit queue
     ec_eoe_flush(eoe);
@@ -225,6 +223,7 @@
         complete_offset = eoe->tx_offset / 32;
     }
     else {
+        // complete size in 32 bit blocks, rounded up.
         complete_offset = remaining_size / 32 + 1;
     }
 
@@ -291,22 +290,6 @@
     return eoe->slave && eoe->opened;
 }
 
-/*****************************************************************************/
-
-/**
-   Prints EoE handler information.
-*/
-
-void ec_eoe_print(const ec_eoe_t *eoe /**< EoE handler */)
-{
-    EC_INFO("  EoE handler %s\n", eoe->dev->name);
-    EC_INFO("    State: %s\n", eoe->opened ? "opened" : "closed");
-    if (eoe->slave)
-        EC_INFO("    Coupled to slave %i.\n", eoe->slave->ring_position);
-    else
-        EC_INFO("    Not coupled.\n");
-}
-
 /******************************************************************************
  *  STATE PROCESSING FUNCTIONS
  *****************************************************************************/
@@ -337,7 +320,7 @@
 
 void ec_eoe_state_rx_check(ec_eoe_t *eoe /**< EoE handler */)
 {
-    if (eoe->datagram.state != EC_CMD_RECEIVED) {
+    if (eoe->datagram.state != EC_DATAGRAM_RECEIVED) {
         eoe->stats.rx_errors++;
         eoe->state = ec_eoe_state_tx_start;
         return;
@@ -368,7 +351,7 @@
     uint8_t frame_number, fragment_offset, fragment_number;
     off_t offset;
 
-    if (eoe->datagram.state != EC_CMD_RECEIVED) {
+    if (eoe->datagram.state != EC_DATAGRAM_RECEIVED) {
         eoe->stats.rx_errors++;
         eoe->state = ec_eoe_state_tx_start;
         return;
@@ -383,114 +366,116 @@
 
     frame_type = EC_READ_U16(data) & 0x000F;
 
-    if (frame_type == 0x00) { // EoE Fragment Request
-        last_fragment = (EC_READ_U16(data) >> 8) & 0x0001;
-        time_appended = (EC_READ_U16(data) >> 9) & 0x0001;
-        fragment_number = EC_READ_U16(data + 2) & 0x003F;
-        fragment_offset = (EC_READ_U16(data + 2) >> 6) & 0x003F;
-        frame_number = (EC_READ_U16(data + 2) >> 12) & 0x000F;
-
-#if EOE_DEBUG_LEVEL > 0
-        EC_DBG("EoE RX fragment %i, offset %i, frame %i%s%s,"
-               " %i octets\n", fragment_number, fragment_offset,
-               frame_number,
-               last_fragment ? ", last fragment" : "",
-               time_appended ? ", + timestamp" : "",
-               time_appended ? rec_size - 8 : rec_size - 4);
-#endif
-
-#if EOE_DEBUG_LEVEL > 1
-        EC_DBG("");
-        for (i = 0; i < rec_size - 4; i++) {
-            printk("%02X ", data[i + 4]);
-            if ((i + 1) % 16 == 0) {
-                printk("\n");
-                EC_DBG("");
-            }
-        }
-        printk("\n");
-#endif
-
-        data_size = time_appended ? rec_size - 8 : rec_size - 4;
-
-        if (!fragment_number) {
-            if (eoe->rx_skb) {
-                EC_WARN("EoE RX freeing old socket buffer...\n");
-                dev_kfree_skb(eoe->rx_skb);
-            }
-
-            // new socket buffer
-            if (!(eoe->rx_skb = dev_alloc_skb(fragment_offset * 32))) {
-                if (printk_ratelimit())
-                    EC_WARN("EoE RX low on mem. frame dropped.\n");
-                eoe->stats.rx_dropped++;
-                eoe->state = ec_eoe_state_tx_start;
-                return;
-            }
-
-            eoe->rx_skb_offset = 0;
-            eoe->rx_skb_size = fragment_offset * 32;
-            eoe->rx_expected_fragment = 0;
-        }
-        else {
-            if (!eoe->rx_skb) {
-                eoe->stats.rx_dropped++;
-                eoe->state = ec_eoe_state_tx_start;
-                return;
-            }
-
-            offset = fragment_offset * 32;
-            if (offset != eoe->rx_skb_offset ||
-                offset + data_size > eoe->rx_skb_size ||
-                fragment_number != eoe->rx_expected_fragment) {
-                eoe->stats.rx_errors++;
-                eoe->state = ec_eoe_state_tx_start;
-                dev_kfree_skb(eoe->rx_skb);
-                eoe->rx_skb = NULL;
-                return;
-            }
-        }
-
-        // copy fragment into socket buffer
-        memcpy(skb_put(eoe->rx_skb, data_size), data + 4, data_size);
-        eoe->rx_skb_offset += data_size;
-
-        if (last_fragment) {
-            // update statistics
-            eoe->stats.rx_packets++;
-            eoe->stats.rx_bytes += eoe->rx_skb->len;
-
-#if EOE_DEBUG_LEVEL > 0
-            EC_DBG("EoE RX frame completed with %u octets.\n",
-                   eoe->rx_skb->len);
-#endif
-
-            // pass socket buffer to network stack
-            eoe->rx_skb->dev = eoe->dev;
-            eoe->rx_skb->protocol = eth_type_trans(eoe->rx_skb, eoe->dev);
-            eoe->rx_skb->ip_summed = CHECKSUM_UNNECESSARY;
-            if (netif_rx(eoe->rx_skb)) {
-                EC_WARN("EoE RX netif_rx failed.\n");
-            }
-            eoe->rx_skb = NULL;
-
-            eoe->state = ec_eoe_state_tx_start;
-        }
-        else {
-            eoe->rx_expected_fragment++;
-#if EOE_DEBUG_LEVEL > 0
-            EC_DBG("EoE RX expecting fragment %i\n",
-                   eoe->rx_expected_fragment);
-#endif
-            eoe->state = ec_eoe_state_rx_start;
-        }
-    }
-    else {
+    if (frame_type != 0x00) {
 #if EOE_DEBUG_LEVEL > 0
         EC_DBG("other frame received.\n");
 #endif
         eoe->stats.rx_dropped++;
         eoe->state = ec_eoe_state_tx_start;
+        return;
+    }
+
+    // EoE Fragment Request received
+
+    last_fragment = (EC_READ_U16(data) >> 8) & 0x0001;
+    time_appended = (EC_READ_U16(data) >> 9) & 0x0001;
+    fragment_number = EC_READ_U16(data + 2) & 0x003F;
+    fragment_offset = (EC_READ_U16(data + 2) >> 6) & 0x003F;
+    frame_number = (EC_READ_U16(data + 2) >> 12) & 0x000F;
+
+#if EOE_DEBUG_LEVEL > 0
+    EC_DBG("EoE RX fragment %i, offset %i, frame %i%s%s,"
+           " %i octets\n", fragment_number, fragment_offset,
+           frame_number,
+           last_fragment ? ", last fragment" : "",
+           time_appended ? ", + timestamp" : "",
+           time_appended ? rec_size - 8 : rec_size - 4);
+#endif
+
+#if EOE_DEBUG_LEVEL > 1
+    EC_DBG("");
+    for (i = 0; i < rec_size - 4; i++) {
+        printk("%02X ", data[i + 4]);
+        if ((i + 1) % 16 == 0) {
+            printk("\n");
+            EC_DBG("");
+        }
+    }
+    printk("\n");
+#endif
+
+    data_size = time_appended ? rec_size - 8 : rec_size - 4;
+
+    if (!fragment_number) {
+        if (eoe->rx_skb) {
+            EC_WARN("EoE RX freeing old socket buffer...\n");
+            dev_kfree_skb(eoe->rx_skb);
+        }
+
+        // new socket buffer
+        if (!(eoe->rx_skb = dev_alloc_skb(fragment_offset * 32))) {
+            if (printk_ratelimit())
+                EC_WARN("EoE RX low on mem. frame dropped.\n");
+            eoe->stats.rx_dropped++;
+            eoe->state = ec_eoe_state_tx_start;
+            return;
+        }
+
+        eoe->rx_skb_offset = 0;
+        eoe->rx_skb_size = fragment_offset * 32;
+        eoe->rx_expected_fragment = 0;
+    }
+    else {
+        if (!eoe->rx_skb) {
+            eoe->stats.rx_dropped++;
+            eoe->state = ec_eoe_state_tx_start;
+            return;
+        }
+
+        offset = fragment_offset * 32;
+        if (offset != eoe->rx_skb_offset ||
+            offset + data_size > eoe->rx_skb_size ||
+            fragment_number != eoe->rx_expected_fragment) {
+            dev_kfree_skb(eoe->rx_skb);
+            eoe->rx_skb = NULL;
+            eoe->stats.rx_errors++;
+            eoe->state = ec_eoe_state_tx_start;
+            return;
+        }
+    }
+
+    // copy fragment into socket buffer
+    memcpy(skb_put(eoe->rx_skb, data_size), data + 4, data_size);
+    eoe->rx_skb_offset += data_size;
+
+    if (last_fragment) {
+        // update statistics
+        eoe->stats.rx_packets++;
+        eoe->stats.rx_bytes += eoe->rx_skb->len;
+
+#if EOE_DEBUG_LEVEL > 0
+        EC_DBG("EoE RX frame completed with %u octets.\n",
+               eoe->rx_skb->len);
+#endif
+
+        // pass socket buffer to network stack
+        eoe->rx_skb->dev = eoe->dev;
+        eoe->rx_skb->protocol = eth_type_trans(eoe->rx_skb, eoe->dev);
+        eoe->rx_skb->ip_summed = CHECKSUM_UNNECESSARY;
+        if (netif_rx(eoe->rx_skb)) {
+            EC_WARN("EoE RX netif_rx failed.\n");
+        }
+        eoe->rx_skb = NULL;
+
+        eoe->state = ec_eoe_state_tx_start;
+    }
+    else {
+        eoe->rx_expected_fragment++;
+#if EOE_DEBUG_LEVEL > 0
+        EC_DBG("EoE RX expecting fragment %i\n",
+               eoe->rx_expected_fragment);
+#endif
+        eoe->state = ec_eoe_state_rx_start;
     }
 }
 
@@ -567,7 +552,7 @@
 
 void ec_eoe_state_tx_sent(ec_eoe_t *eoe /**< EoE handler */)
 {
-    if (eoe->datagram.state != EC_CMD_RECEIVED) {
+    if (eoe->datagram.state != EC_DATAGRAM_RECEIVED) {
         eoe->stats.tx_errors++;
         eoe->state = ec_eoe_state_rx_start;
         return;
--- a/master/ethernet.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/ethernet.h	Thu Aug 03 12:59:01 2006 +0000
@@ -98,6 +98,5 @@
 void ec_eoe_clear(ec_eoe_t *);
 void ec_eoe_run(ec_eoe_t *);
 unsigned int ec_eoe_active(const ec_eoe_t *);
-void ec_eoe_print(const ec_eoe_t *);
 
 /*****************************************************************************/
--- a/master/fsm.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/fsm.c	Thu Aug 03 12:59:01 2006 +0000
@@ -46,32 +46,35 @@
 
 void ec_fsm_master_start(ec_fsm_t *);
 void ec_fsm_master_broadcast(ec_fsm_t *);
-void ec_fsm_master_proc_states(ec_fsm_t *);
-void ec_fsm_master_scan(ec_fsm_t *);
-void ec_fsm_master_states(ec_fsm_t *);
+void ec_fsm_master_read_states(ec_fsm_t *);
 void ec_fsm_master_validate_vendor(ec_fsm_t *);
 void ec_fsm_master_validate_product(ec_fsm_t *);
-void ec_fsm_master_reconfigure(ec_fsm_t *);
-void ec_fsm_master_address(ec_fsm_t *);
-void ec_fsm_master_conf(ec_fsm_t *);
-void ec_fsm_master_eeprom(ec_fsm_t *);
-
-void ec_fsm_slave_start_reading(ec_fsm_t *);
-void ec_fsm_slave_read_state(ec_fsm_t *);
-void ec_fsm_slave_read_base(ec_fsm_t *);
-void ec_fsm_slave_read_dl(ec_fsm_t *);
-void ec_fsm_slave_eeprom_size(ec_fsm_t *);
-void ec_fsm_slave_fetch_eeprom(ec_fsm_t *);
-void ec_fsm_slave_fetch_eeprom2(ec_fsm_t *);
-void ec_fsm_slave_end(ec_fsm_t *);
-
-void ec_fsm_slave_conf(ec_fsm_t *);
-void ec_fsm_slave_sync(ec_fsm_t *);
-void ec_fsm_slave_preop(ec_fsm_t *);
-void ec_fsm_slave_fmmu(ec_fsm_t *);
-void ec_fsm_slave_saveop(ec_fsm_t *);
-void ec_fsm_slave_op(ec_fsm_t *);
-void ec_fsm_slave_op2(ec_fsm_t *);
+void ec_fsm_master_rewrite_addresses(ec_fsm_t *);
+void ec_fsm_master_configure_slave(ec_fsm_t *);
+void ec_fsm_master_scan_slaves(ec_fsm_t *);
+void ec_fsm_master_write_eeprom(ec_fsm_t *);
+
+void ec_fsm_startup_start(ec_fsm_t *);
+void ec_fsm_startup_broadcast(ec_fsm_t *);
+void ec_fsm_startup_scan(ec_fsm_t *);
+
+void ec_fsm_configuration_start(ec_fsm_t *);
+void ec_fsm_configuration_conf(ec_fsm_t *);
+
+void ec_fsm_slavescan_start(ec_fsm_t *);
+void ec_fsm_slavescan_address(ec_fsm_t *);
+void ec_fsm_slavescan_state(ec_fsm_t *);
+void ec_fsm_slavescan_base(ec_fsm_t *);
+void ec_fsm_slavescan_datalink(ec_fsm_t *);
+void ec_fsm_slavescan_eeprom_size(ec_fsm_t *);
+void ec_fsm_slavescan_eeprom_data(ec_fsm_t *);
+
+void ec_fsm_slaveconf_init(ec_fsm_t *);
+void ec_fsm_slaveconf_sync(ec_fsm_t *);
+void ec_fsm_slaveconf_preop(ec_fsm_t *);
+void ec_fsm_slaveconf_fmmu(ec_fsm_t *);
+void ec_fsm_slaveconf_saveop(ec_fsm_t *);
+void ec_fsm_slaveconf_op(ec_fsm_t *);
 
 void ec_fsm_sii_start_reading(ec_fsm_t *);
 void ec_fsm_sii_read_check(ec_fsm_t *);
@@ -79,17 +82,16 @@
 void ec_fsm_sii_start_writing(ec_fsm_t *);
 void ec_fsm_sii_write_check(ec_fsm_t *);
 void ec_fsm_sii_write_check2(ec_fsm_t *);
-void ec_fsm_sii_end(ec_fsm_t *);
-void ec_fsm_sii_error(ec_fsm_t *);
 
 void ec_fsm_change_start(ec_fsm_t *);
 void ec_fsm_change_check(ec_fsm_t *);
 void ec_fsm_change_status(ec_fsm_t *);
 void ec_fsm_change_code(ec_fsm_t *);
 void ec_fsm_change_ack(ec_fsm_t *);
-void ec_fsm_change_ack2(ec_fsm_t *);
-void ec_fsm_change_end(ec_fsm_t *);
-void ec_fsm_change_error(ec_fsm_t *);
+void ec_fsm_change_check_ack(ec_fsm_t *);
+
+void ec_fsm_end(ec_fsm_t *);
+void ec_fsm_error(ec_fsm_t *);
 
 /*****************************************************************************/
 
@@ -99,7 +101,7 @@
 
 int ec_fsm_init(ec_fsm_t *fsm, /**< finite state machine */
                 ec_master_t *master /**< EtherCAT master */
-    )
+                )
 {
     fsm->master = master;
     fsm->master_state = ec_fsm_master_start;
@@ -151,8 +153,224 @@
     fsm->master_state(fsm);
 }
 
+/*****************************************************************************/
+
+void ec_fsm_startup(ec_fsm_t *fsm)
+{
+    fsm->master_state = ec_fsm_startup_start;
+}
+
+/*****************************************************************************/
+
+int ec_fsm_startup_running(ec_fsm_t *fsm)
+{
+    return fsm->master_state != ec_fsm_end &&
+        fsm->master_state != ec_fsm_error;
+}
+
+/*****************************************************************************/
+
+int ec_fsm_startup_success(ec_fsm_t *fsm)
+{
+    return fsm->master_state == ec_fsm_end;
+}
+
+/*****************************************************************************/
+
+void ec_fsm_configuration(ec_fsm_t *fsm)
+{
+    fsm->master_state = ec_fsm_configuration_start;
+}
+
+/*****************************************************************************/
+
+int ec_fsm_configuration_running(ec_fsm_t *fsm)
+{
+    return fsm->master_state != ec_fsm_end &&
+        fsm->master_state != ec_fsm_error;
+}
+
+/*****************************************************************************/
+
+int ec_fsm_configuration_success(ec_fsm_t *fsm)
+{
+    return fsm->master_state == ec_fsm_end;
+}
+
 /******************************************************************************
- *  master state machine
+ *  master startup state machine
+ *****************************************************************************/
+
+/**
+   Master state: START.
+   Starts with getting slave count and slave states.
+*/
+
+void ec_fsm_startup_start(ec_fsm_t *fsm)
+{
+    ec_datagram_brd(&fsm->datagram, 0x0130, 2);
+    ec_master_queue_datagram(fsm->master, &fsm->datagram);
+    fsm->master_state = ec_fsm_startup_broadcast;
+}
+
+/*****************************************************************************/
+
+/**
+   Master state: BROADCAST.
+   Processes the broadcast read slave count and slaves states.
+*/
+
+void ec_fsm_startup_broadcast(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+    unsigned int i;
+    ec_slave_t *slave;
+    ec_master_t *master = fsm->master;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED) {
+        EC_ERR("Failed tor receive broadcast datagram.\n");
+        fsm->master_state = ec_fsm_error;
+        return;
+    }
+
+    EC_INFO("Scanning bus.\n");
+
+    ec_master_clear_slaves(master);
+
+    master->slave_count = datagram->working_counter;
+
+    if (!master->slave_count) {
+        // no slaves present -> finish state machine.
+        fsm->master_state = ec_fsm_end;
+        return;
+    }
+
+    // init slaves
+    for (i = 0; i < master->slave_count; i++) {
+        if (!(slave = (ec_slave_t *) kmalloc(sizeof(ec_slave_t),
+                                             GFP_KERNEL))) {
+            EC_ERR("Failed to allocate slave %i!\n", i);
+            fsm->master_state = ec_fsm_error;
+            return;
+        }
+
+        if (ec_slave_init(slave, master, i, i + 1)) {
+            fsm->master_state = ec_fsm_error;
+            return;
+        }
+
+        if (kobject_add(&slave->kobj)) {
+            EC_ERR("Failed to add kobject.\n");
+            kobject_put(&slave->kobj); // free
+            fsm->master_state = ec_fsm_error;
+            return;
+        }
+
+        list_add_tail(&slave->list, &master->slaves);
+    }
+
+    // begin scanning of slaves
+    fsm->slave = list_entry(master->slaves.next, ec_slave_t, list);
+    fsm->slave_state = ec_fsm_slavescan_start;
+    fsm->master_state = ec_fsm_startup_scan;
+    fsm->master_state(fsm); // execute immediately
+    return;
+}
+
+/*****************************************************************************/
+
+/**
+   Master state: SCAN.
+   Executes the sub-statemachine for the scanning of a slave.
+*/
+
+void ec_fsm_startup_scan(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_master_t *master = fsm->master;
+    ec_slave_t *slave = fsm->slave;
+
+    fsm->slave_state(fsm); // execute slave state machine
+
+    if (fsm->slave_state == ec_fsm_error) {
+        EC_ERR("Slave scanning failed.\n");
+        fsm->master_state = ec_fsm_error;
+        return;
+    }
+
+    if (fsm->slave_state != ec_fsm_end) return;
+
+    // another slave to scan?
+    if (slave->list.next != &master->slaves) {
+        fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
+        fsm->slave_state = ec_fsm_slavescan_start;
+        fsm->slave_state(fsm); // execute immediately
+        return;
+    }
+
+    EC_INFO("Bus scanning completed.\n");
+
+    ec_master_calc_addressing(master);
+
+    fsm->master_state = ec_fsm_end;
+}
+
+/******************************************************************************
+ *  master configuration state machine
+ *****************************************************************************/
+
+void ec_fsm_configuration_start(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_master_t *master = fsm->master;
+
+    if (list_empty(&master->slaves)) {
+        fsm->master_state = ec_fsm_end;
+        return;
+    }
+
+    // begin configuring slaves
+    fsm->slave = list_entry(master->slaves.next, ec_slave_t, list);
+    fsm->slave_state = ec_fsm_slaveconf_init;
+    fsm->change_new = EC_SLAVE_STATE_INIT;
+    fsm->change_state = ec_fsm_change_start;
+    fsm->master_state = ec_fsm_configuration_conf;
+    fsm->master_state(fsm); // execute immediately
+}
+
+/*****************************************************************************/
+
+/**
+   Master state: CONF.
+*/
+
+void ec_fsm_configuration_conf(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_master_t *master = fsm->master;
+    ec_slave_t *slave = fsm->slave;
+
+    fsm->slave_state(fsm); // execute slave's state machine
+
+    if (fsm->slave_state == ec_fsm_error) {
+        fsm->master_state = ec_fsm_error;
+        return;
+    }
+
+    if (fsm->slave_state != ec_fsm_end) return;
+
+    // another slave to configure?
+    if (slave->list.next != &master->slaves) {
+        fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
+        fsm->slave_state = ec_fsm_slaveconf_init;
+        fsm->change_new = EC_SLAVE_STATE_INIT;
+        fsm->change_state = ec_fsm_change_start;
+        fsm->master_state(fsm); // execute immediately
+        return;
+    }
+
+    fsm->master_state = ec_fsm_end;
+}
+
+/******************************************************************************
+ *  operation / idle state machine
  *****************************************************************************/
 
 /**
@@ -181,7 +399,7 @@
     ec_slave_t *slave;
     ec_master_t *master = fsm->master;
 
-    if (datagram->state != EC_CMD_RECEIVED) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED) {
         if (!master->device->link_state) {
             fsm->master_slaves_responding = 0;
             list_for_each_entry(slave, &master->slaves, list) {
@@ -205,7 +423,7 @@
                 fsm->master_slaves_responding,
                 fsm->master_slaves_responding == 1 ? "" : "s");
 
-        if (master->mode == EC_MASTER_MODE_RUNNING) {
+        if (master->mode == EC_MASTER_MODE_OPERATION) {
             if (fsm->master_slaves_responding == master->slave_count) {
                 fsm->master_validation = 1; // start validation later
             }
@@ -216,19 +434,21 @@
     }
 
     if (states_change) {
-        EC_INFO("Slave states: ");
-        ec_print_states(fsm->master_slave_states);
-        printk(".\n");
-    }
-
-    // topology change in free-run mode: clear all slaves and scan the bus
-    if (topology_change && master->mode == EC_MASTER_MODE_FREERUN) {
+        char states[25];
+        ec_state_string(fsm->master_slave_states, states);
+        EC_INFO("Slave states: %s.\n", states);
+    }
+
+    // topology change in idle mode: clear all slaves and scan the bus
+    if (topology_change && master->mode == EC_MASTER_MODE_IDLE) {
         EC_INFO("Scanning bus.\n");
 
         ec_master_eoe_stop(master);
         ec_master_clear_slaves(master);
 
-        if (!fsm->master_slaves_responding) {
+        master->slave_count = datagram->working_counter;
+
+        if (!master->slave_count) {
             // no slaves present -> finish state machine.
             fsm->master_state = ec_fsm_master_start;
             fsm->master_state(fsm); // execute immediately
@@ -236,16 +456,19 @@
         }
 
         // init slaves
-        for (i = 0; i < fsm->master_slaves_responding; i++) {
+        for (i = 0; i < master->slave_count; i++) {
             if (!(slave = (ec_slave_t *) kmalloc(sizeof(ec_slave_t),
                                                  GFP_ATOMIC))) {
                 EC_ERR("Failed to allocate slave %i!\n", i);
+                ec_master_clear_slaves(master);
                 fsm->master_state = ec_fsm_master_start;
                 fsm->master_state(fsm); // execute immediately
                 return;
             }
 
             if (ec_slave_init(slave, master, i, i + 1)) {
+                // freeing of "slave" already done
+                ec_master_clear_slaves(master);
                 fsm->master_state = ec_fsm_master_start;
                 fsm->master_state(fsm); // execute immediately
                 return;
@@ -254,6 +477,7 @@
             if (kobject_add(&slave->kobj)) {
                 EC_ERR("Failed to add kobject.\n");
                 kobject_put(&slave->kobj); // free
+                ec_master_clear_slaves(master);
                 fsm->master_state = ec_fsm_master_start;
                 fsm->master_state(fsm); // execute immediately
                 return;
@@ -264,8 +488,8 @@
 
         // begin scanning of slaves
         fsm->slave = list_entry(master->slaves.next, ec_slave_t, list);
-        fsm->slave_state = ec_fsm_slave_start_reading;
-        fsm->master_state = ec_fsm_master_scan;
+        fsm->slave_state = ec_fsm_slavescan_start;
+        fsm->master_state = ec_fsm_master_scan_slaves;
         fsm->master_state(fsm); // execute immediately
         return;
     }
@@ -274,7 +498,77 @@
     fsm->slave = list_entry(master->slaves.next, ec_slave_t, list);
     ec_datagram_nprd(&fsm->datagram, fsm->slave->station_address, 0x0130, 2);
     ec_master_queue_datagram(master, &fsm->datagram);
-    fsm->master_state = ec_fsm_master_states;
+    fsm->master_state = ec_fsm_master_read_states;
+}
+
+/*****************************************************************************/
+
+/**
+   Master action: PROC_STATES.
+   Processes the slave states.
+*/
+
+void ec_fsm_master_action_process_states(ec_fsm_t *fsm
+                                         /**< finite state machine */
+                                         )
+{
+    ec_master_t *master = fsm->master;
+    ec_slave_t *slave;
+    char old_state[25], new_state[25];
+
+    // check if any slaves are not in the state, they're supposed to be
+    list_for_each_entry(slave, &master->slaves, list) {
+        if (slave->error_flag ||
+            !slave->online ||
+            slave->requested_state == EC_SLAVE_STATE_UNKNOWN ||
+            slave->current_state == slave->requested_state) continue;
+
+        ec_state_string(slave->current_state, old_state);
+        ec_state_string(slave->requested_state, new_state);
+        EC_INFO("Changing state of slave %i from %s to %s.\n",
+                slave->ring_position, old_state, new_state);
+
+        fsm->slave = slave;
+        fsm->slave_state = ec_fsm_slaveconf_init;
+        fsm->change_new = EC_SLAVE_STATE_INIT;
+        fsm->change_state = ec_fsm_change_start;
+        fsm->master_state = ec_fsm_master_configure_slave;
+        fsm->master_state(fsm); // execute immediately
+        return;
+    }
+
+    // Check, if EoE processing has to be started
+    ec_master_eoe_start(master);
+
+    if (master->mode == EC_MASTER_MODE_IDLE) {
+        // nothing to configure. check for pending EEPROM write operations.
+        list_for_each_entry(slave, &master->slaves, list) {
+            if (!slave->new_eeprom_data) continue;
+
+            if (!slave->online || slave->error_flag) {
+                kfree(slave->new_eeprom_data);
+                slave->new_eeprom_data = NULL;
+                EC_ERR("Discarding EEPROM data, slave %i not ready.\n",
+                       slave->ring_position);
+                continue;
+            }
+
+            // found pending EEPROM write operation. execute it!
+            EC_INFO("Writing EEPROM of slave %i...\n", slave->ring_position);
+            fsm->sii_offset = 0x0000;
+            memcpy(fsm->sii_value, slave->new_eeprom_data, 2);
+            fsm->sii_mode = 1;
+            fsm->sii_state = ec_fsm_sii_start_writing;
+            fsm->slave = slave;
+            fsm->master_state = ec_fsm_master_write_eeprom;
+            fsm->master_state(fsm); // execute immediately
+            return;
+        }
+    }
+
+    // nothing to do. restart master state machine.
+    fsm->master_state = ec_fsm_master_start;
+    fsm->master_state(fsm); // execute immediately
 }
 
 /*****************************************************************************/
@@ -289,18 +583,20 @@
     ec_master_t *master = fsm->master;
     ec_slave_t *slave = fsm->slave;
 
-    // have all states been read?
+    // is there another slave to query?
     if (slave->list.next != &master->slaves) {
         // process next slave
         fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
         ec_datagram_nprd(&fsm->datagram, fsm->slave->station_address,
                          0x0130, 2);
         ec_master_queue_datagram(master, &fsm->datagram);
-        fsm->master_state = ec_fsm_master_states;
-        return;
-    }
-
-    // all slave stated read; check, if a bus validation has to be done
+        fsm->master_state = ec_fsm_master_read_states;
+        return;
+    }
+
+    // all slave states read
+
+    // check, if a bus validation has to be done
     if (fsm->master_validation) {
         fsm->master_validation = 0;
         list_for_each_entry(slave, &master->slaves, list) {
@@ -318,8 +614,7 @@
         }
     }
 
-    fsm->master_state = ec_fsm_master_proc_states;
-    fsm->master_state(fsm); // execute immediately
+    ec_fsm_master_action_process_states(fsm);
 }
 
 /*****************************************************************************/
@@ -329,13 +624,13 @@
    Fetches the AL- and online state of a slave.
 */
 
-void ec_fsm_master_states(ec_fsm_t *fsm /**< finite state machine */)
+void ec_fsm_master_read_states(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_slave_t *slave = fsm->slave;
     ec_datagram_t *datagram = &fsm->datagram;
     uint8_t new_state;
 
-    if (datagram->state != EC_CMD_RECEIVED) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED) {
         fsm->master_state = ec_fsm_master_start;
         fsm->master_state(fsm); // execute immediately
         return;
@@ -354,19 +649,19 @@
     // slave responded
     new_state = EC_READ_U8(datagram->data);
     if (!slave->online) { // slave was offline before
+        char cur_state[25];
         slave->online = 1;
         slave->error_flag = 0; // clear error flag
         slave->current_state = new_state;
-        EC_INFO("Slave %i: online (", slave->ring_position);
-        ec_print_states(new_state);
-        printk(").\n");
+        ec_state_string(slave->current_state, cur_state);
+        EC_INFO("Slave %i: online (%s).\n", slave->ring_position, cur_state);
     }
     else if (new_state != slave->current_state) {
-        EC_INFO("Slave %i: ", slave->ring_position);
-        ec_print_states(slave->current_state);
-        printk(" -> ");
-        ec_print_states(new_state);
-        printk(".\n");
+        char old_state[25], cur_state[25];
+        ec_state_string(slave->current_state, old_state);
+        ec_state_string(new_state, cur_state);
+        EC_INFO("Slave %i: %s -> %s.\n",
+                slave->ring_position, old_state, cur_state);
         slave->current_state = new_state;
     }
 
@@ -376,71 +671,6 @@
 /*****************************************************************************/
 
 /**
-   Master state: PROC_STATES.
-   Processes the slave states.
-*/
-
-void ec_fsm_master_proc_states(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_master_t *master = fsm->master;
-    ec_slave_t *slave;
-
-    // check if any slaves are not in the state, they're supposed to be
-    list_for_each_entry(slave, &master->slaves, list) {
-        if (slave->error_flag ||
-            !slave->online ||
-            slave->requested_state == EC_SLAVE_STATE_UNKNOWN ||
-            slave->current_state == slave->requested_state) continue;
-
-        EC_INFO("Changing state of slave %i from ", slave->ring_position);
-        ec_print_states(slave->current_state);
-        printk(" to ");
-        ec_print_states(slave->requested_state);
-        printk(".\n");
-
-        fsm->slave = slave;
-        fsm->slave_state = ec_fsm_slave_conf;
-        fsm->change_new = EC_SLAVE_STATE_INIT;
-        fsm->change_state = ec_fsm_change_start;
-        fsm->master_state = ec_fsm_master_conf;
-        fsm->master_state(fsm); // execute immediately
-        return;
-    }
-
-    if (master->mode == EC_MASTER_MODE_FREERUN) {
-        // nothing to configure. check for pending EEPROM write operations.
-        list_for_each_entry(slave, &master->slaves, list) {
-            if (!slave->new_eeprom_data) continue;
-
-            if (!slave->online || slave->error_flag) {
-                kfree(slave->new_eeprom_data);
-                slave->new_eeprom_data = NULL;
-                EC_ERR("Discarding EEPROM data, slave %i not ready.\n",
-                       slave->ring_position);
-                continue;
-            }
-
-            // found pending EEPROM write operation. execute it!
-            EC_INFO("Writing EEPROM of slave %i...\n", slave->ring_position);
-            fsm->sii_offset = 0x0000;
-            memcpy(fsm->sii_value, slave->new_eeprom_data, 2);
-            fsm->sii_mode = 1;
-            fsm->sii_state = ec_fsm_sii_start_writing;
-            fsm->slave = slave;
-            fsm->master_state = ec_fsm_master_eeprom;
-            fsm->master_state(fsm); // execute immediately
-            return;
-        }
-    }
-
-    // nothing to do. restart master state machine.
-    fsm->master_state = ec_fsm_master_start;
-    fsm->master_state(fsm); // execute immediately
-}
-
-/*****************************************************************************/
-
-/**
    Master state: VALIDATE_VENDOR.
    Validates the vendor ID of a slave.
 */
@@ -451,7 +681,7 @@
 
     fsm->sii_state(fsm); // execute SII state machine
 
-    if (fsm->sii_state == ec_fsm_sii_error) {
+    if (fsm->sii_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
         EC_ERR("Failed to validate vendor ID of slave %i.\n",
                slave->ring_position);
@@ -460,7 +690,7 @@
         return;
     }
 
-    if (fsm->sii_state != ec_fsm_sii_end) return;
+    if (fsm->sii_state != ec_fsm_end) return;
 
     if (EC_READ_U32(fsm->sii_value) != slave->sii_vendor_id) {
         EC_ERR("Slave %i: invalid vendor ID!\n", slave->ring_position);
@@ -480,6 +710,37 @@
 /*****************************************************************************/
 
 /**
+   Master action: ADDRESS.
+   Looks for slave, that have lost their configuration and writes
+   their station address, so that they can be reconfigured later.
+*/
+
+void ec_fsm_master_action_addresses(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+
+    while (fsm->slave->online) {
+        if (fsm->slave->list.next == &fsm->master->slaves) { // last slave?
+            fsm->master_state = ec_fsm_master_start;
+            fsm->master_state(fsm); // execute immediately
+            return;
+        }
+        // check next slave
+        fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
+    }
+
+    EC_INFO("Reinitializing slave %i.\n", fsm->slave->ring_position);
+
+    // write station address
+    ec_datagram_apwr(datagram, fsm->slave->ring_position, 0x0010, 2);
+    EC_WRITE_U16(datagram->data, fsm->slave->station_address);
+    ec_master_queue_datagram(fsm->master, datagram);
+    fsm->master_state = ec_fsm_master_rewrite_addresses;
+}
+
+/*****************************************************************************/
+
+/**
    Master state: VALIDATE_PRODUCT.
    Validates the product ID of a slave.
 */
@@ -490,7 +751,7 @@
 
     fsm->sii_state(fsm); // execute SII state machine
 
-    if (fsm->sii_state == ec_fsm_sii_error) {
+    if (fsm->sii_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
         EC_ERR("Failed to validate product code of slave %i.\n",
                slave->ring_position);
@@ -499,7 +760,7 @@
         return;
     }
 
-    if (fsm->sii_state != ec_fsm_sii_end) return;
+    if (fsm->sii_state != ec_fsm_end) return;
 
     if (EC_READ_U32(fsm->sii_value) != slave->sii_product_code) {
         EC_ERR("Slave %i: invalid product code!\n", slave->ring_position);
@@ -513,7 +774,8 @@
     // have all states been validated?
     if (slave->list.next == &fsm->master->slaves) {
         fsm->slave = list_entry(fsm->master->slaves.next, ec_slave_t, list);
-        fsm->master_state = ec_fsm_master_reconfigure;
+        // start writing addresses to offline slaves
+        ec_fsm_master_action_addresses(fsm);
         return;
     }
 
@@ -529,47 +791,19 @@
 /*****************************************************************************/
 
 /**
-   Master state: RECONFIGURE.
-   Looks for slave, that have lost their configuration and writes
-   their station address, so that they can be reconfigured later.
-*/
-
-void ec_fsm_master_reconfigure(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-
-    while (fsm->slave->online) {
-        if (fsm->slave->list.next == &fsm->master->slaves) { // last slave?
-            fsm->master_state = ec_fsm_master_start;
-            fsm->master_state(fsm); // execute immediately
-            return;
-        }
-        // check next slave
-        fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
-    }
-
-    EC_INFO("Reinitializing slave %i.\n", fsm->slave->ring_position);
-
-    // write station address
-    ec_datagram_apwr(datagram, fsm->slave->ring_position, 0x0010, 2);
-    EC_WRITE_U16(datagram->data, fsm->slave->station_address);
-    ec_master_queue_datagram(fsm->master, datagram);
-    fsm->master_state = ec_fsm_master_address;
-}
-
-/*****************************************************************************/
-
-/**
    Master state: ADDRESS.
    Checks, if the new station address has been written to the slave.
 */
 
-void ec_fsm_master_address(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_slave_t *slave = fsm->slave;
-    ec_datagram_t *datagram = &fsm->datagram;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+void ec_fsm_master_rewrite_addresses(ec_fsm_t *fsm
+                                     /**< finite state machine */
+                                     )
+{
+    ec_slave_t *slave = fsm->slave;
+    ec_datagram_t *datagram = &fsm->datagram;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         EC_ERR("Failed to write station address on slave %i.\n",
                slave->ring_position);
     }
@@ -582,8 +816,8 @@
 
     // check next slave
     fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
-    fsm->master_state = ec_fsm_master_reconfigure;
-    fsm->master_state(fsm); // execute immediately
+    // Write new station address to slave
+    ec_fsm_master_action_addresses(fsm);
 }
 
 /*****************************************************************************/
@@ -593,93 +827,44 @@
    Executes the sub-statemachine for the scanning of a slave.
 */
 
-void ec_fsm_master_scan(ec_fsm_t *fsm /**< finite state machine */)
+void ec_fsm_master_scan_slaves(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_master_t *master = fsm->master;
     ec_slave_t *slave = fsm->slave;
-    uint16_t coupler_index, coupler_subindex;
-    uint16_t reverse_coupler_index, current_coupler_index;
-    ec_slave_ident_t *ident;
+
 
     fsm->slave_state(fsm); // execute slave state machine
 
-    if (fsm->slave_state != ec_fsm_slave_end) return;
-
-    // have all slaves been fetched?
-    if (slave->list.next == &master->slaves) {
-        EC_INFO("Bus scanning completed.\n");
-
-        // identify all slaves and calculate coupler addressing
-
-        coupler_index = 0;
-        reverse_coupler_index = 0xFFFF;
-        current_coupler_index = 0x3FFF;
-        coupler_subindex = 0;
-
-        list_for_each_entry(slave, &master->slaves, list)
-        {
-            // search for identification in "database"
-            ident = slave_idents;
-            while (ident->type) {
-                if (ident->vendor_id == slave->sii_vendor_id
-                    && ident->product_code == slave->sii_product_code) {
-                    slave->type = ident->type;
-                    break;
-                }
-                ident++;
-            }
-
-            if (!slave->type) {
-                EC_WARN("Unknown slave device (vendor 0x%08X,"
-                        " code 0x%08X) at position %i.\n",
-                        slave->sii_vendor_id, slave->sii_product_code,
-                        slave->ring_position);
-            }
-            else {
-                // if the slave is a bus coupler, change adressing base
-                if (slave->type->special == EC_TYPE_BUS_COUPLER) {
-                    if (slave->sii_alias)
-                        current_coupler_index = reverse_coupler_index--;
-                    else
-                        current_coupler_index = coupler_index++;
-                    coupler_subindex = 0;
-                }
-            }
-
-            // determine initial state.
-            if ((slave->type &&
-                 (slave->type->special == EC_TYPE_BUS_COUPLER ||
-                  slave->type->special == EC_TYPE_INFRA))) {
-                slave->requested_state = EC_SLAVE_STATE_OP;
-            }
-            else {
-                if (master->mode == EC_MASTER_MODE_RUNNING)
-                    slave->requested_state = EC_SLAVE_STATE_PREOP;
-                else
-                    slave->requested_state = EC_SLAVE_STATE_INIT;
-            }
-            slave->error_flag = 0;
-
-            // calculate coupler-based slave address
-            slave->coupler_index = current_coupler_index;
-            slave->coupler_subindex = coupler_subindex;
-            coupler_subindex++;
-        }
-
-        if (master->mode == EC_MASTER_MODE_FREERUN) {
-            // start EoE processing
-            ec_master_eoe_start(master);
-        }
-
-        fsm->master_state = ec_fsm_master_start;
-        fsm->master_state(fsm); // execute immediately
-        return;
-    }
-
-    // process next slave
-    fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
-    fsm->slave_state = ec_fsm_slave_start_reading;
-    fsm->slave_state(fsm); // execute immediately
+    if (fsm->slave_state != ec_fsm_end
+        && fsm->slave_state != ec_fsm_error) return;
+
+    // another slave to fetch?
+    if (slave->list.next != &master->slaves) {
+        fsm->slave = list_entry(fsm->slave->list.next, ec_slave_t, list);
+        fsm->slave_state = ec_fsm_slavescan_start;
+        fsm->slave_state(fsm); // execute immediately
+        return;
+    }
+
+    EC_INFO("Bus scanning completed.\n");
+
+    ec_master_calc_addressing(master);
+
+    // determine initial states.
+    list_for_each_entry(slave, &master->slaves, list) {
+        if (ec_slave_is_coupler(slave)) {
+            slave->requested_state = EC_SLAVE_STATE_OP;
+        }
+        else {
+            if (master->mode == EC_MASTER_MODE_OPERATION)
+                slave->requested_state = EC_SLAVE_STATE_PREOP;
+            else
+                slave->requested_state = EC_SLAVE_STATE_INIT;
+        }
+    }
+
+    fsm->master_state = ec_fsm_master_start;
+    fsm->master_state(fsm); // execute immediately
 }
 
 /*****************************************************************************/
@@ -689,12 +874,16 @@
    Starts configuring a slave.
 */
 
-void ec_fsm_master_conf(ec_fsm_t *fsm /**< finite state machine */)
+void ec_fsm_master_configure_slave(ec_fsm_t *fsm
+                                   /**< finite state machine */
+                                   )
 {
     fsm->slave_state(fsm); // execute slave's state machine
-    if (fsm->slave_state != ec_fsm_slave_end) return;
-    fsm->master_state = ec_fsm_master_proc_states;
-    fsm->master_state(fsm); // execute immediately
+
+    if (fsm->slave_state != ec_fsm_end
+        && fsm->slave_state != ec_fsm_error) return;
+
+    ec_fsm_master_action_process_states(fsm);
 }
 
 /*****************************************************************************/
@@ -703,13 +892,13 @@
    Master state: EEPROM.
 */
 
-void ec_fsm_master_eeprom(ec_fsm_t *fsm /**< finite state machine */)
+void ec_fsm_master_write_eeprom(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_slave_t *slave = fsm->slave;
 
     fsm->sii_state(fsm); // execute SII state machine
 
-    if (fsm->sii_state == ec_fsm_sii_error) {
+    if (fsm->sii_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
         EC_ERR("Failed to write EEPROM contents to slave %i.\n",
                slave->ring_position);
@@ -720,7 +909,7 @@
         return;
     }
 
-    if (fsm->sii_state != ec_fsm_sii_end) return;
+    if (fsm->sii_state != ec_fsm_end) return;
 
     fsm->sii_offset++;
     if (fsm->sii_offset < slave->new_eeprom_size) {
@@ -735,6 +924,8 @@
     kfree(slave->new_eeprom_data);
     slave->new_eeprom_data = NULL;
 
+    // TODO: Evaluate new EEPROM contents!
+
     // restart master state machine.
     fsm->master_state = ec_fsm_master_start;
     fsm->master_state(fsm); // execute immediately
@@ -742,7 +933,7 @@
 }
 
 /******************************************************************************
- *  slave state machine
+ *  slave scan state machine
  *****************************************************************************/
 
 /**
@@ -751,7 +942,7 @@
    slave, according to its ring position.
 */
 
-void ec_fsm_slave_start_reading(ec_fsm_t *fsm /**< finite state machine */)
+void ec_fsm_slavescan_start(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_datagram_t *datagram = &fsm->datagram;
 
@@ -759,22 +950,23 @@
     ec_datagram_apwr(datagram, fsm->slave->ring_position, 0x0010, 2);
     EC_WRITE_U16(datagram->data, fsm->slave->station_address);
     ec_master_queue_datagram(fsm->master, datagram);
-    fsm->slave_state = ec_fsm_slave_read_state;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: READ_STATUS.
-*/
-
-void ec_fsm_slave_read_state(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    fsm->slave_state = ec_fsm_slavescan_address;
+}
+
+/*****************************************************************************/
+
+/**
+   Slave state: ADDRESS.
+*/
+
+void ec_fsm_slavescan_address(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to write station address of slave %i.\n",
                fsm->slave->ring_position);
         return;
@@ -783,23 +975,24 @@
     // Read AL state
     ec_datagram_nprd(datagram, fsm->slave->station_address, 0x0130, 2);
     ec_master_queue_datagram(fsm->master, datagram);
-    fsm->slave_state = ec_fsm_slave_read_base;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: READ_BASE.
-*/
-
-void ec_fsm_slave_read_base(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-    ec_slave_t *slave = fsm->slave;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    fsm->slave_state = ec_fsm_slavescan_state;
+}
+
+/*****************************************************************************/
+
+/**
+   Slave state: STATE.
+*/
+
+void ec_fsm_slavescan_state(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+    ec_slave_t *slave = fsm->slave;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to read AL state of slave %i.\n",
                fsm->slave->ring_position);
         return;
@@ -815,23 +1008,24 @@
     // read base data
     ec_datagram_nprd(datagram, fsm->slave->station_address, 0x0000, 6);
     ec_master_queue_datagram(fsm->master, datagram);
-    fsm->slave_state = ec_fsm_slave_read_dl;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: READ_DL.
-*/
-
-void ec_fsm_slave_read_dl(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-    ec_slave_t *slave = fsm->slave;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    fsm->slave_state = ec_fsm_slavescan_base;
+}
+
+/*****************************************************************************/
+
+/**
+   Slave state: BASE.
+*/
+
+void ec_fsm_slavescan_base(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+    ec_slave_t *slave = fsm->slave;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to read base data of slave %i.\n",
                slave->ring_position);
         return;
@@ -849,26 +1043,26 @@
     // read data link status
     ec_datagram_nprd(datagram, slave->station_address, 0x0110, 2);
     ec_master_queue_datagram(slave->master, datagram);
-    fsm->slave_state = ec_fsm_slave_eeprom_size;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: EEPROM_SIZE.
-   Read the actual size of the EEPROM to allocate the EEPROM image.
-*/
-
-void ec_fsm_slave_eeprom_size(ec_fsm_t *fsm /**< finite state machine */)
+    fsm->slave_state = ec_fsm_slavescan_datalink;
+}
+
+/*****************************************************************************/
+
+/**
+   Slave state: DATALINK.
+*/
+
+void ec_fsm_slavescan_datalink(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_datagram_t *datagram = &fsm->datagram;
     ec_slave_t *slave = fsm->slave;
     uint16_t dl_status;
     unsigned int i;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to read DL status of slave %i.\n",
                slave->ring_position);
         return;
@@ -886,17 +1080,17 @@
     fsm->sii_offset = 0x0040; // first category header
     fsm->sii_mode = 1;
     fsm->sii_state = ec_fsm_sii_start_reading;
-    fsm->slave_state = ec_fsm_slave_fetch_eeprom;
+    fsm->slave_state = ec_fsm_slavescan_eeprom_size;
     fsm->slave_state(fsm); // execute state immediately
 }
 
 /*****************************************************************************/
 
 /**
-   Slave state: FETCH_EEPROM.
-*/
-
-void ec_fsm_slave_fetch_eeprom(ec_fsm_t *fsm /**< finite state machine */)
+   Slave state: EEPROM_SIZE.
+*/
+
+void ec_fsm_slavescan_eeprom_size(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_slave_t *slave = fsm->slave;
     uint16_t cat_type, cat_size;
@@ -904,15 +1098,15 @@
     // execute SII state machine
     fsm->sii_state(fsm);
 
-    if (fsm->sii_state == ec_fsm_sii_error) {
+    if (fsm->sii_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to read EEPROM size of slave %i.\n",
                slave->ring_position);
         return;
     }
 
-    if (fsm->sii_state != ec_fsm_sii_end) return;
+    if (fsm->sii_state != ec_fsm_end) return;
 
     cat_type = EC_READ_U16(fsm->sii_value);
     cat_size = EC_READ_U16(fsm->sii_value + 2);
@@ -935,7 +1129,7 @@
     if (!(slave->eeprom_data =
           (uint8_t *) kmalloc(slave->eeprom_size, GFP_ATOMIC))) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to allocate EEPROM data on slave %i.\n",
                slave->ring_position);
         return;
@@ -946,17 +1140,17 @@
     fsm->sii_offset = 0x0000;
     fsm->sii_mode = 1;
     fsm->sii_state = ec_fsm_sii_start_reading;
-    fsm->slave_state = ec_fsm_slave_fetch_eeprom2;
+    fsm->slave_state = ec_fsm_slavescan_eeprom_data;
     fsm->slave_state(fsm); // execute state immediately
 }
 
 /*****************************************************************************/
 
 /**
-   Slave state: FETCH_EEPROM2.
-*/
-
-void ec_fsm_slave_fetch_eeprom2(ec_fsm_t *fsm /**< finite state machine */)
+   Slave state: EEPROM_DATA.
+*/
+
+void ec_fsm_slavescan_eeprom_data(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_slave_t *slave = fsm->slave;
     uint16_t *cat_word, cat_type, cat_size;
@@ -964,15 +1158,15 @@
     // execute SII state machine
     fsm->sii_state(fsm);
 
-    if (fsm->sii_state == ec_fsm_sii_error) {
+    if (fsm->sii_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to fetch EEPROM contents of slave %i.\n",
                slave->ring_position);
         return;
     }
 
-    if (fsm->sii_state != ec_fsm_sii_end) return;
+    if (fsm->sii_state != ec_fsm_end) return;
 
     // 2 words fetched
 
@@ -1026,8 +1220,7 @@
                     goto end;
                 break;
             case 0x001E:
-                if (ec_slave_fetch_general(slave, (uint8_t *) (cat_word + 2)))
-                    goto end;
+                ec_slave_fetch_general(slave, (uint8_t *) (cat_word + 2));
                 break;
             case 0x0028:
                 break;
@@ -1054,87 +1247,54 @@
         cat_word += cat_size + 2;
     }
 
+    fsm->slave_state = ec_fsm_end;
+    return;
+
 end:
+    EC_ERR("Failed to analyze category data.\n");
     fsm->slave->error_flag = 1;
-    fsm->slave_state = ec_fsm_slave_end;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: CONF.
-*/
-
-void ec_fsm_slave_conf(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_slave_t *slave = fsm->slave;
-    ec_master_t *master = fsm->master;
-    ec_datagram_t *datagram = &fsm->datagram;
+    fsm->slave_state = ec_fsm_error;
+}
+
+/******************************************************************************
+ *  slave configuration state machine
+ *****************************************************************************/
+
+/**
+   Slave state: INIT.
+*/
+
+void ec_fsm_slaveconf_init(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_slave_t *slave = fsm->slave;
+    ec_datagram_t *datagram = &fsm->datagram;
+    const ec_sii_sync_t *sync;
 
     fsm->change_state(fsm); // execute state change state machine
 
-    if (fsm->change_state == ec_fsm_change_error) {
+    if (fsm->change_state == ec_fsm_error) {
         slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
-        return;
-    }
-
-    if (fsm->change_state != ec_fsm_change_end) return;
+        fsm->slave_state = ec_fsm_error;
+        return;
+    }
+
+    if (fsm->change_state != ec_fsm_end) return;
 
     // slave is now in INIT
     if (slave->current_state == slave->requested_state) {
-        fsm->slave_state = ec_fsm_slave_end; // successful
-        return;
-    }
-
-    // check for slave registration
-    if (!slave->type) {
-        EC_WARN("Slave %i has unknown type!\n", slave->ring_position);
+        fsm->slave_state = ec_fsm_end; // successful
+        return;
     }
 
     // check and reset CRC fault counters
     //ec_slave_check_crc(slave);
-
-    if (!slave->base_fmmu_count) { // no fmmus
-        fsm->slave_state = ec_fsm_slave_sync;
-        fsm->slave_state(fsm); // execute immediately
-        return;
-    }
-
-    // reset FMMUs
-    ec_datagram_npwr(datagram, slave->station_address, 0x0600,
-                     EC_FMMU_SIZE * slave->base_fmmu_count);
-    memset(datagram->data, 0x00, EC_FMMU_SIZE * slave->base_fmmu_count);
-    ec_master_queue_datagram(master, datagram);
-    fsm->slave_state = ec_fsm_slave_sync;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: SYNC.
-   Configure sync managers.
-*/
-
-void ec_fsm_slave_sync(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-    ec_slave_t *slave = fsm->slave;
-    unsigned int j;
-    const ec_sync_t *sync;
-    ec_eeprom_sync_t *eeprom_sync, mbox_sync;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
-        slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
-        EC_ERR("Failed to reset FMMUs of slave %i.\n",
-               slave->ring_position);
-        return;
-    }
+    // TODO: Implement state machine for CRC checking.
 
     if (!slave->base_sync_count) { // no sync managers
-        fsm->slave_state = ec_fsm_slave_preop;
-        fsm->slave_state(fsm); // execute immediately
+        fsm->slave_state = ec_fsm_slaveconf_preop;
+        fsm->change_new = EC_SLAVE_STATE_PREOP;
+        fsm->change_state = ec_fsm_change_start;
+        fsm->change_state(fsm); // execute immediately
         return;
     }
 
@@ -1143,92 +1303,54 @@
                      EC_SYNC_SIZE * slave->base_sync_count);
     memset(datagram->data, 0x00, EC_SYNC_SIZE * slave->base_sync_count);
 
-    // known slave type, take type's SM information
-    if (slave->type) {
-        for (j = 0; slave->type->sync_managers[j] && j < EC_MAX_SYNC; j++) {
-            sync = slave->type->sync_managers[j];
-            ec_sync_config(sync, slave, datagram->data + EC_SYNC_SIZE * j);
-        }
-    }
-
-    // unknown type, but slave has mailbox
-    else if (slave->sii_mailbox_protocols)
-    {
-        // does it supply sync manager configurations in its EEPROM?
-        if (!list_empty(&slave->eeprom_syncs)) {
-            list_for_each_entry(eeprom_sync, &slave->eeprom_syncs, list) {
-                if (eeprom_sync->index >= slave->base_sync_count) {
-                    fsm->slave->error_flag = 1;
-                    fsm->slave_state = ec_fsm_slave_end;
-                    EC_ERR("Invalid sync manager configuration found!");
-                    return;
-                }
-                ec_eeprom_sync_config(eeprom_sync,
-                                      datagram->data + EC_SYNC_SIZE
-                                      * eeprom_sync->index);
-            }
-        }
-
-        // no sync manager information; guess mailbox settings
-        else {
-            mbox_sync.physical_start_address =
-                slave->sii_rx_mailbox_offset;
-            mbox_sync.length = slave->sii_rx_mailbox_size;
-            mbox_sync.control_register = 0x26;
-            mbox_sync.enable = 1;
-            ec_eeprom_sync_config(&mbox_sync, datagram->data);
-
-            mbox_sync.physical_start_address =
-                slave->sii_tx_mailbox_offset;
-            mbox_sync.length = slave->sii_tx_mailbox_size;
-            mbox_sync.control_register = 0x22;
-            mbox_sync.enable = 1;
-            ec_eeprom_sync_config(&mbox_sync,
-                                  datagram->data + EC_SYNC_SIZE);
-        }
-
-        EC_INFO("Mailbox configured for unknown slave %i\n",
-                slave->ring_position);
+    list_for_each_entry(sync, &slave->sii_syncs, list) {
+        if (sync->index >= slave->base_sync_count) {
+            EC_ERR("Invalid sync manager configuration found!");
+            fsm->slave->error_flag = 1;
+            fsm->slave_state = ec_fsm_error;
+            return;
+        }
+        ec_sync_config(sync, slave,
+                       datagram->data + EC_SYNC_SIZE * sync->index);
     }
 
     ec_master_queue_datagram(fsm->master, datagram);
-    fsm->slave_state = ec_fsm_slave_preop;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: PREOP.
-   Change slave state to PREOP.
-*/
-
-void ec_fsm_slave_preop(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-    ec_slave_t *slave = fsm->slave;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    fsm->slave_state = ec_fsm_slaveconf_sync;
+}
+
+/*****************************************************************************/
+
+/**
+   Slave state: SYNC.
+*/
+
+void ec_fsm_slaveconf_sync(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+    ec_slave_t *slave = fsm->slave;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to set sync managers on slave %i.\n",
                slave->ring_position);
         return;
     }
 
+    fsm->slave_state = ec_fsm_slaveconf_preop;
     fsm->change_new = EC_SLAVE_STATE_PREOP;
     fsm->change_state = ec_fsm_change_start;
-    fsm->slave_state = ec_fsm_slave_fmmu;
     fsm->change_state(fsm); // execute immediately
 }
 
 /*****************************************************************************/
 
 /**
-   Slave state: FMMU.
-   Configure FMMUs.
-*/
-
-void ec_fsm_slave_fmmu(ec_fsm_t *fsm /**< finite state machine */)
+   Slave state: PREOP.
+*/
+
+void ec_fsm_slaveconf_preop(ec_fsm_t *fsm /**< finite state machine */)
 {
     ec_slave_t *slave = fsm->slave;
     ec_master_t *master = fsm->master;
@@ -1237,29 +1359,25 @@
 
     fsm->change_state(fsm); // execute state change state machine
 
-    if (fsm->change_state == ec_fsm_change_error) {
+    if (fsm->change_state == ec_fsm_error) {
         slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
-        return;
-    }
-
-    if (fsm->change_state != ec_fsm_change_end) return;
+        fsm->slave_state = ec_fsm_error;
+        return;
+    }
+
+    if (fsm->change_state != ec_fsm_end) return;
 
     // slave is now in PREOP
     if (slave->current_state == slave->requested_state) {
-        fsm->slave_state = ec_fsm_slave_end; // successful
-        return;
-    }
-
-    // stop activation here for slaves without type
-    if (!slave->type) {
-        fsm->slave_state = ec_fsm_slave_end; // successful
+        fsm->slave_state = ec_fsm_end; // successful
         return;
     }
 
     if (!slave->base_fmmu_count) {
-        fsm->slave_state = ec_fsm_slave_saveop;
-        fsm->slave_state(fsm); // execute immediately
+        fsm->slave_state = ec_fsm_slaveconf_saveop;
+        fsm->change_new = EC_SLAVE_STATE_SAVEOP;
+        fsm->change_state = ec_fsm_change_start;
+        fsm->change_state(fsm); // execute immediately
         return;
     }
 
@@ -1273,31 +1391,30 @@
     }
 
     ec_master_queue_datagram(master, datagram);
-    fsm->slave_state = ec_fsm_slave_saveop;
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: SAVEOP.
-   Set slave state to SAVEOP.
-*/
-
-void ec_fsm_slave_saveop(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-
-    if (fsm->slave->base_fmmu_count && (datagram->state != EC_CMD_RECEIVED ||
-                                        datagram->working_counter != 1)) {
+    fsm->slave_state = ec_fsm_slaveconf_fmmu;
+}
+
+/*****************************************************************************/
+
+/**
+   Slave state: FMMU.
+*/
+
+void ec_fsm_slaveconf_fmmu(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
+        fsm->slave_state = ec_fsm_error;
         EC_ERR("Failed to set FMMUs on slave %i.\n",
                fsm->slave->ring_position);
         return;
     }
 
     // set state to SAVEOP
-    fsm->slave_state = ec_fsm_slave_op;
+    fsm->slave_state = ec_fsm_slaveconf_saveop;
     fsm->change_new = EC_SLAVE_STATE_SAVEOP;
     fsm->change_state = ec_fsm_change_start;
     fsm->change_state(fsm); // execute immediately
@@ -1306,30 +1423,29 @@
 /*****************************************************************************/
 
 /**
-   Slave state: OP.
-   Set slave state to OP.
-*/
-
-void ec_fsm_slave_op(ec_fsm_t *fsm /**< finite state machine */)
+   Slave state: SAVEOP.
+*/
+
+void ec_fsm_slaveconf_saveop(ec_fsm_t *fsm /**< finite state machine */)
 {
     fsm->change_state(fsm); // execute state change state machine
 
-    if (fsm->change_state == ec_fsm_change_error) {
+    if (fsm->change_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
-        return;
-    }
-
-    if (fsm->change_state != ec_fsm_change_end) return;
+        fsm->slave_state = ec_fsm_error;
+        return;
+    }
+
+    if (fsm->change_state != ec_fsm_end) return;
 
     // slave is now in SAVEOP
     if (fsm->slave->current_state == fsm->slave->requested_state) {
-        fsm->slave_state = ec_fsm_slave_end; // successful
+        fsm->slave_state = ec_fsm_end; // successful
         return;
     }
 
     // set state to OP
-    fsm->slave_state = ec_fsm_slave_op2;
+    fsm->slave_state = ec_fsm_slaveconf_op;
     fsm->change_new = EC_SLAVE_STATE_OP;
     fsm->change_state = ec_fsm_change_start;
     fsm->change_state(fsm); // execute immediately
@@ -1338,35 +1454,23 @@
 /*****************************************************************************/
 
 /**
-   Slave state: OP2
-   Executes the change state machine, until the OP state is set.
-*/
-
-void ec_fsm_slave_op2(ec_fsm_t *fsm /**< finite state machine */)
+   Slave state: OP
+*/
+
+void ec_fsm_slaveconf_op(ec_fsm_t *fsm /**< finite state machine */)
 {
     fsm->change_state(fsm); // execute state change state machine
 
-    if (fsm->change_state == ec_fsm_change_error) {
+    if (fsm->change_state == ec_fsm_error) {
         fsm->slave->error_flag = 1;
-        fsm->slave_state = ec_fsm_slave_end;
-        return;
-    }
-
-    if (fsm->change_state != ec_fsm_change_end) return;
+        fsm->slave_state = ec_fsm_error;
+        return;
+    }
+
+    if (fsm->change_state != ec_fsm_end) return;
 
     // slave is now in OP
-    fsm->slave_state = ec_fsm_slave_end; // successful
-}
-
-/*****************************************************************************/
-
-/**
-   Slave state: END.
-   End state of the slave state machine.
-*/
-
-void ec_fsm_slave_end(ec_fsm_t *fsm /**< finite state machine */)
-{
+    fsm->slave_state = ec_fsm_end; // successful
 }
 
 /******************************************************************************
@@ -1408,9 +1512,10 @@
 {
     ec_datagram_t *datagram = &fsm->datagram;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         EC_ERR("SII: Reception of read datagram failed.\n");
-        fsm->sii_state = ec_fsm_sii_error;
+        fsm->sii_state = ec_fsm_error;
         return;
     }
 
@@ -1439,9 +1544,10 @@
 {
     ec_datagram_t *datagram = &fsm->datagram;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         EC_ERR("SII: Reception of check/fetch datagram failed.\n");
-        fsm->sii_state = ec_fsm_sii_error;
+        fsm->sii_state = ec_fsm_error;
         return;
     }
 
@@ -1450,7 +1556,7 @@
         // still busy... timeout?
         if (get_cycles() - fsm->sii_start >= (cycles_t) 10 * cpu_khz) {
             EC_ERR("SII: Timeout.\n");
-            fsm->sii_state = ec_fsm_sii_error;
+            fsm->sii_state = ec_fsm_error;
 #if 0
             EC_DBG("SII busy: %02X %02X %02X %02X\n",
                    EC_READ_U8(datagram->data + 0),
@@ -1481,7 +1587,7 @@
 
     // SII value received.
     memcpy(fsm->sii_value, datagram->data + 6, 4);
-    fsm->sii_state = ec_fsm_sii_end;
+    fsm->sii_state = ec_fsm_end;
 }
 
 /*****************************************************************************/
@@ -1515,9 +1621,10 @@
 {
     ec_datagram_t *datagram = &fsm->datagram;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         EC_ERR("SII: Reception of write datagram failed.\n");
-        fsm->sii_state = ec_fsm_sii_error;
+        fsm->sii_state = ec_fsm_error;
         return;
     }
 
@@ -1539,9 +1646,10 @@
 {
     ec_datagram_t *datagram = &fsm->datagram;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
         EC_ERR("SII: Reception of write check datagram failed.\n");
-        fsm->sii_state = ec_fsm_sii_error;
+        fsm->sii_state = ec_fsm_error;
         return;
     }
 
@@ -1549,7 +1657,7 @@
         // still busy... timeout?
         if (get_cycles() - fsm->sii_start >= (cycles_t) 10 * cpu_khz) {
             EC_ERR("SII: Write timeout.\n");
-            fsm->sii_state = ec_fsm_sii_error;
+            fsm->sii_state = ec_fsm_error;
         }
 
         // issue check/fetch datagram again
@@ -1557,33 +1665,11 @@
     }
     else if (EC_READ_U8(datagram->data + 1) & 0x40) {
         EC_ERR("SII: Write operation failed!\n");
-        fsm->sii_state = ec_fsm_sii_error;
+        fsm->sii_state = ec_fsm_error;
     }
     else { // success
-        fsm->sii_state = ec_fsm_sii_end;
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   SII state: END.
-   End state of the slave SII state machine.
-*/
-
-void ec_fsm_sii_end(ec_fsm_t *fsm /**< finite state machine */)
-{
-}
-
-/*****************************************************************************/
-
-/**
-   SII state: ERROR.
-   End state of the slave SII state machine.
-*/
-
-void ec_fsm_sii_error(ec_fsm_t *fsm /**< finite state machine */)
-{
+        fsm->sii_state = ec_fsm_end;
+    }
 }
 
 /******************************************************************************
@@ -1599,6 +1685,8 @@
     ec_datagram_t *datagram = &fsm->datagram;
     ec_slave_t *slave = fsm->slave;
 
+    fsm->change_start = get_cycles();
+
     // write new state to slave
     ec_datagram_npwr(datagram, slave->station_address, 0x0120, 2);
     EC_WRITE_U16(datagram->data, fsm->change_new);
@@ -1617,17 +1705,25 @@
     ec_datagram_t *datagram = &fsm->datagram;
     ec_slave_t *slave = fsm->slave;
 
-    if (datagram->state != EC_CMD_RECEIVED) {
-        fsm->change_state = ec_fsm_change_error;
+    if (datagram->state != EC_DATAGRAM_RECEIVED) {
+        fsm->change_state = ec_fsm_error;
         EC_ERR("Failed to send state datagram to slave %i!\n",
                fsm->slave->ring_position);
         return;
     }
 
     if (datagram->working_counter != 1) {
-        fsm->change_state = ec_fsm_change_error;
-        EC_ERR("Failed to set state 0x%02X on slave %i: Slave did not"
-               " respond.\n", fsm->change_new, fsm->slave->ring_position);
+        if (get_cycles() - fsm->change_start >= (cycles_t) 100 * cpu_khz) {
+            fsm->change_state = ec_fsm_error;
+            EC_ERR("Failed to set state 0x%02X on slave %i: Slave did not"
+                   " respond.\n", fsm->change_new, fsm->slave->ring_position);
+            return;
+        }
+
+        // repeat writing new state to slave
+        ec_datagram_npwr(datagram, slave->station_address, 0x0120, 2);
+        EC_WRITE_U16(datagram->data, fsm->change_new);
+        ec_master_queue_datagram(fsm->master, datagram);
         return;
     }
 
@@ -1650,8 +1746,9 @@
     ec_datagram_t *datagram = &fsm->datagram;
     ec_slave_t *slave = fsm->slave;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
-        fsm->change_state = ec_fsm_change_error;
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
+        fsm->change_state = ec_fsm_error;
         EC_ERR("Failed to check state 0x%02X on slave %i.\n",
                fsm->change_new, slave->ring_position);
         return;
@@ -1661,7 +1758,7 @@
 
     if (slave->current_state == fsm->change_new) {
         // state has been set successfully
-        fsm->change_state = ec_fsm_change_end;
+        fsm->change_state = ec_fsm_end;
         return;
     }
 
@@ -1680,7 +1777,7 @@
 
     if (get_cycles() - fsm->change_start >= (cycles_t) 10 * cpu_khz) {
         // timeout while checking
-        fsm->change_state = ec_fsm_change_error;
+        fsm->change_state = ec_fsm_error;
         EC_ERR("Timeout while setting state 0x%02X on slave %i.\n",
                fsm->change_new, slave->ring_position);
         return;
@@ -1710,10 +1807,24 @@
     {0x0019, "No valid outputs"},
     {0x001A, "Synchronisation error"},
     {0x001B, "Sync manager watchdog"},
+    {0x001C, "Invalid sync manager types"},
+    {0x001D, "Invalid output configuration"},
+    {0x001E, "Invalid input configuration"},
+    {0x001F, "Invalid watchdog configuration"},
     {0x0020, "Slave needs cold start"},
     {0x0021, "Slave needs INIT"},
     {0x0022, "Slave needs PREOP"},
     {0x0023, "Slave needs SAVEOP"},
+    {0x0030, "Invalid DC SYNCH configuration"},
+    {0x0031, "Invalid DC latch configuration"},
+    {0x0032, "PLL error"},
+    {0x0033, "Invalid DC IO error"},
+    {0x0034, "Invalid DC timeout error"},
+    {0x0042, "MBOX EOE"},
+    {0x0043, "MBOX COE"},
+    {0x0044, "MBOX FOE"},
+    {0x0045, "MBOX SOE"},
+    {0x004F, "MBOX VOE"},
     {}
 };
 
@@ -1730,8 +1841,9 @@
     uint32_t code;
     const ec_code_msg_t *al_msg;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
-        fsm->change_state = ec_fsm_change_error;
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
+        fsm->change_state = ec_fsm_error;
         EC_ERR("Reception of AL status code datagram failed.\n");
         return;
     }
@@ -1765,68 +1877,81 @@
     ec_datagram_t *datagram = &fsm->datagram;
     ec_slave_t *slave = fsm->slave;
 
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
-        fsm->change_state = ec_fsm_change_error;
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
+        fsm->change_state = ec_fsm_error;
         EC_ERR("Reception of state ack datagram failed.\n");
         return;
     }
 
+    fsm->change_start = get_cycles();
+
     // read new AL status
     ec_datagram_nprd(datagram, slave->station_address, 0x0130, 2);
     ec_master_queue_datagram(fsm->master, datagram);
-    fsm->change_state = ec_fsm_change_ack2;
-}
-
-/*****************************************************************************/
-
-/**
-   Change state: ACK.
-   Acknowledge 2.
-*/
-
-void ec_fsm_change_ack2(ec_fsm_t *fsm /**< finite state machine */)
-{
-    ec_datagram_t *datagram = &fsm->datagram;
-    ec_slave_t *slave = fsm->slave;
-
-    if (datagram->state != EC_CMD_RECEIVED || datagram->working_counter != 1) {
-        fsm->change_state = ec_fsm_change_error;
+    fsm->change_state = ec_fsm_change_check_ack;
+}
+
+/*****************************************************************************/
+
+/**
+   Change state: CHECK ACK.
+*/
+
+void ec_fsm_change_check_ack(ec_fsm_t *fsm /**< finite state machine */)
+{
+    ec_datagram_t *datagram = &fsm->datagram;
+    ec_slave_t *slave = fsm->slave;
+    ec_slave_state_t ack_state;
+
+    if (datagram->state != EC_DATAGRAM_RECEIVED
+        || datagram->working_counter != 1) {
+        fsm->change_state = ec_fsm_error;
         EC_ERR("Reception of state ack check datagram failed.\n");
         return;
     }
 
-    slave->current_state = EC_READ_U8(datagram->data);
-
-    if (slave->current_state == fsm->change_new) {
-        fsm->change_state = ec_fsm_change_error;
+    ack_state = EC_READ_U8(datagram->data);
+
+    if (ack_state == slave->current_state) {
+        fsm->change_state = ec_fsm_error;
         EC_INFO("Acknowleged state 0x%02X on slave %i.\n",
                 slave->current_state, slave->ring_position);
         return;
     }
 
-    fsm->change_state = ec_fsm_change_error;
-    EC_WARN("Failed to acknowledge state 0x%02X on slave %i"
-            " - Timeout!\n", fsm->change_new, slave->ring_position);
-}
-
-/*****************************************************************************/
-
-/**
-   Change state: END.
-*/
-
-void ec_fsm_change_end(ec_fsm_t *fsm /**< finite state machine */)
-{
-}
-
-/*****************************************************************************/
-
-/**
-   Change state: ERROR.
-*/
-
-void ec_fsm_change_error(ec_fsm_t *fsm /**< finite state machine */)
-{
-}
-
-/*****************************************************************************/
+    if (get_cycles() - fsm->change_start >= (cycles_t) 100 * cpu_khz) {
+        // timeout while checking
+        slave->current_state = EC_SLAVE_STATE_UNKNOWN;
+        fsm->change_state = ec_fsm_error;
+        EC_ERR("Timeout while acknowleging state 0x%02X on slave %i.\n",
+               fsm->change_new, slave->ring_position);
+        return;
+    }
+
+    // reread new AL status
+    ec_datagram_nprd(datagram, slave->station_address, 0x0130, 2);
+    ec_master_queue_datagram(fsm->master, datagram);
+}
+
+/*****************************************************************************/
+
+/**
+   State: ERROR.
+*/
+
+void ec_fsm_error(ec_fsm_t *fsm /**< finite state machine */)
+{
+}
+
+/*****************************************************************************/
+
+/**
+   State: END.
+*/
+
+void ec_fsm_end(ec_fsm_t *fsm /**< finite state machine */)
+{
+}
+
+/*****************************************************************************/
--- a/master/fsm.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/fsm.h	Thu Aug 03 12:59:01 2006 +0000
@@ -41,6 +41,7 @@
 #ifndef __EC_STATES__
 #define __EC_STATES__
 
+#include "globals.h"
 #include "../include/ecrt.h"
 #include "datagram.h"
 #include "slave.h"
@@ -84,6 +85,14 @@
 void ec_fsm_reset(ec_fsm_t *);
 void ec_fsm_execute(ec_fsm_t *);
 
+void ec_fsm_startup(ec_fsm_t *);
+int ec_fsm_startup_running(ec_fsm_t *);
+int ec_fsm_startup_success(ec_fsm_t *);
+
+void ec_fsm_configuration(ec_fsm_t *);
+int ec_fsm_configuration_running(ec_fsm_t *);
+int ec_fsm_configuration_success(ec_fsm_t *);
+
 /*****************************************************************************/
 
 #endif
--- a/master/globals.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/globals.h	Thu Aug 03 12:59:01 2006 +0000
@@ -51,7 +51,7 @@
 #define EC_MASTER_VERSION_MAIN  1
 
 /** master sub version (after the dot) */
-#define EC_MASTER_VERSION_SUB   0
+#define EC_MASTER_VERSION_SUB   1
 
 /** master extra version (just a string) */
 #define EC_MASTER_VERSION_EXTRA "trunk"
@@ -65,6 +65,9 @@
 /** clock frequency for the EoE state machines */
 #define EC_EOE_FREQUENCY 1000
 
+/** datagram timeout in microseconds */
+#define EC_IO_TIMEOUT 500
+
 /******************************************************************************
  *  EtherCAT protocol
  *****************************************************************************/
@@ -170,9 +173,9 @@
 
 /*****************************************************************************/
 
-extern void ec_print_data(const uint8_t *, size_t);
-extern void ec_print_data_diff(const uint8_t *, const uint8_t *, size_t);
-extern void ec_print_states(uint8_t);
+void ec_print_data(const uint8_t *, size_t);
+void ec_print_data_diff(const uint8_t *, const uint8_t *, size_t);
+size_t ec_state_string(uint8_t, char *);
 
 /*****************************************************************************/
 
@@ -192,4 +195,3 @@
 /*****************************************************************************/
 
 #endif
-
--- a/master/mailbox.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/mailbox.c	Thu Aug 03 12:59:01 2006 +0000
@@ -165,83 +165,3 @@
 }
 
 /*****************************************************************************/
-
-/**
-   Sends a mailbox datagram and waits for its reception.
-   \return pointer to the received data
-*/
-
-uint8_t *ec_slave_mbox_simple_io(const ec_slave_t *slave, /**< slave */
-                                 ec_datagram_t *datagram, /**< datagram */
-                                 size_t *size /**< size of the received data */
-                                 )
-{
-    uint8_t type;
-
-    type = EC_READ_U8(datagram->data + 5);
-
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("Mailbox checking failed on slave %i!\n",
-               slave->ring_position);
-        return NULL;
-    }
-
-    return ec_slave_mbox_simple_receive(slave, datagram, type, size);
-}
-
-/*****************************************************************************/
-
-/**
-   Waits for the reception of a mailbox datagram.
-   \return pointer to the received data
-*/
-
-uint8_t *ec_slave_mbox_simple_receive(const ec_slave_t *slave, /**< slave */
-                                      ec_datagram_t *datagram, /**< datagram */
-                                      uint8_t type, /**< expected protocol */
-                                      size_t *size /**< received data size */
-                                      )
-{
-    cycles_t start, end, timeout;
-
-    start = get_cycles();
-    timeout = (cycles_t) 100 * cpu_khz; // 100ms
-
-    while (1)
-    {
-        if (ec_slave_mbox_prepare_check(slave, datagram)) return NULL;
-        if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-            EC_ERR("Mailbox checking failed on slave %i!\n",
-                   slave->ring_position);
-            return NULL;
-        }
-
-        end = get_cycles();
-
-        if (ec_slave_mbox_check(datagram))
-            break; // proceed with receiving data
-
-        if ((end - start) >= timeout) {
-            EC_ERR("Mailbox check - Slave %i timed out.\n",
-                   slave->ring_position);
-            return NULL;
-        }
-
-        udelay(100);
-    }
-
-    if (ec_slave_mbox_prepare_fetch(slave, datagram)) return NULL;
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("Mailbox receiving failed on slave %i!\n",
-               slave->ring_position);
-        return NULL;
-    }
-
-    if (unlikely(slave->master->debug_level) > 1)
-        EC_DBG("Mailbox receive took %ius.\n",
-               ((unsigned int) (end - start) * 1000 / cpu_khz));
-
-    return ec_slave_mbox_fetch(slave, datagram, type, size);
-}
-
-/*****************************************************************************/
--- a/master/master.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/master.c	Thu Aug 03 12:59:01 2006 +0000
@@ -48,14 +48,14 @@
 #include "globals.h"
 #include "master.h"
 #include "slave.h"
-#include "types.h"
 #include "device.h"
 #include "datagram.h"
 #include "ethernet.h"
 
 /*****************************************************************************/
 
-void ec_master_freerun(void *);
+void ec_master_sync_io(ec_master_t *);
+void ec_master_idle_run(void *);
 void ec_master_eoe_run(unsigned long);
 ssize_t ec_show_master_attribute(struct kobject *, struct attribute *, char *);
 ssize_t ec_store_master_attribute(struct kobject *, struct attribute *,
@@ -68,11 +68,13 @@
 EC_SYSFS_READ_ATTR(slave_count);
 EC_SYSFS_READ_ATTR(mode);
 EC_SYSFS_READ_WRITE_ATTR(eeprom_write_enable);
+EC_SYSFS_READ_WRITE_ATTR(debug_level);
 
 static struct attribute *ec_def_attrs[] = {
     &attr_slave_count,
     &attr_mode,
     &attr_eeprom_write_enable,
+    &attr_debug_level,
     NULL,
 };
 
@@ -98,7 +100,7 @@
 
 int ec_master_init(ec_master_t *master, /**< EtherCAT master */
                    unsigned int index, /**< master index */
-                   unsigned int eoe_devices /**< number of EoE devices */
+                   unsigned int eoeif_count /**< number of EoE interfaces */
                    )
 {
     ec_eoe_t *eoe, *next_eoe;
@@ -113,8 +115,7 @@
     INIT_LIST_HEAD(&master->datagram_queue);
     INIT_LIST_HEAD(&master->domains);
     INIT_LIST_HEAD(&master->eoe_handlers);
-    ec_datagram_init(&master->simple_datagram);
-    INIT_WORK(&master->freerun_work, ec_master_freerun, (void *) master);
+    INIT_WORK(&master->idle_work, ec_master_idle_run, (void *) master);
     init_timer(&master->eoe_timer);
     master->eoe_timer.function = ec_master_eoe_run;
     master->eoe_timer.data = (unsigned long) master;
@@ -128,7 +129,7 @@
     }
 
     // create EoE handlers
-    for (i = 0; i < eoe_devices; i++) {
+    for (i = 0; i < eoeif_count; i++) {
         if (!(eoe = (ec_eoe_t *) kmalloc(sizeof(ec_eoe_t), GFP_KERNEL))) {
             EC_ERR("Failed to allocate EoE-Object.\n");
             goto out_clear_eoe;
@@ -184,7 +185,6 @@
 
     ec_master_reset(master);
     ec_fsm_clear(&master->fsm);
-    ec_datagram_clear(&master->simple_datagram);
     destroy_workqueue(master->workqueue);
 
     // clear EoE objects
@@ -216,14 +216,14 @@
     ec_domain_t *domain, *next_d;
 
     ec_master_eoe_stop(master);
-    ec_master_freerun_stop(master);
+    ec_master_idle_stop(master);
     ec_master_clear_slaves(master);
 
     // empty datagram queue
     list_for_each_entry_safe(datagram, next_c,
                              &master->datagram_queue, queue) {
         list_del_init(&datagram->queue);
-        datagram->state = EC_CMD_ERROR;
+        datagram->state = EC_DATAGRAM_ERROR;
     }
 
     // clear domains
@@ -235,7 +235,6 @@
 
     master->datagram_index = 0;
     master->debug_level = 0;
-    master->timeout = 500; // 500us
 
     master->stats.timeouts = 0;
     master->stats.delayed = 0;
@@ -243,7 +242,7 @@
     master->stats.unmatched = 0;
     master->stats.t_last = 0;
 
-    master->mode = EC_MASTER_MODE_IDLE;
+    master->mode = EC_MASTER_MODE_ORPHANED;
 
     master->request_cb = NULL;
     master->release_cb = NULL;
@@ -287,7 +286,7 @@
     // check, if the datagram is already queued
     list_for_each_entry(queued_datagram, &master->datagram_queue, queue) {
         if (queued_datagram == datagram) {
-            datagram->state = EC_CMD_QUEUED;
+            datagram->state = EC_DATAGRAM_QUEUED;
             if (unlikely(master->debug_level))
                 EC_WARN("datagram already queued.\n");
             return;
@@ -295,7 +294,7 @@
     }
 
     list_add_tail(&datagram->queue, &master->datagram_queue);
-    datagram->state = EC_CMD_QUEUED;
+    datagram->state = EC_DATAGRAM_QUEUED;
 }
 
 /*****************************************************************************/
@@ -317,7 +316,7 @@
     frame_count = 0;
     t_start = get_cycles();
 
-    if (unlikely(master->debug_level > 0))
+    if (unlikely(master->debug_level > 1))
         EC_DBG("ec_master_send_datagrams\n");
 
     do {
@@ -329,7 +328,7 @@
 
         // fill current frame with datagrams
         list_for_each_entry(datagram, &master->datagram_queue, queue) {
-            if (datagram->state != EC_CMD_QUEUED) continue;
+            if (datagram->state != EC_DATAGRAM_QUEUED) continue;
 
             // does the current datagram fit in the frame?
             datagram_size = EC_DATAGRAM_HEADER_SIZE + datagram->data_size
@@ -339,11 +338,11 @@
                 break;
             }
 
-            datagram->state = EC_CMD_SENT;
+            datagram->state = EC_DATAGRAM_SENT;
             datagram->t_sent = t_start;
             datagram->index = master->datagram_index++;
 
-            if (unlikely(master->debug_level > 0))
+            if (unlikely(master->debug_level > 1))
                 EC_DBG("adding datagram 0x%02X\n", datagram->index);
 
             // set "datagram following" flag in previous frame
@@ -369,7 +368,7 @@
         }
 
         if (cur_data - frame_data == EC_FRAME_HEADER_SIZE) {
-            if (unlikely(master->debug_level > 0))
+            if (unlikely(master->debug_level > 1))
                 EC_DBG("nothing to send.\n");
             break;
         }
@@ -382,7 +381,7 @@
         while (cur_data - frame_data < ETH_ZLEN - ETH_HLEN)
             EC_WRITE_U8(cur_data++, 0x00);
 
-        if (unlikely(master->debug_level > 0))
+        if (unlikely(master->debug_level > 1))
             EC_DBG("frame size: %i\n", cur_data - frame_data);
 
         // send frame
@@ -391,7 +390,7 @@
     }
     while (more_datagrams_waiting);
 
-    if (unlikely(master->debug_level > 0)) {
+    if (unlikely(master->debug_level > 1)) {
         t_end = get_cycles();
         EC_DBG("ec_master_send_datagrams sent %i frames in %ius.\n",
                frame_count, (unsigned int) (t_end - t_start) * 1000 / cpu_khz);
@@ -454,7 +453,7 @@
         // search for matching datagram in the queue
         matched = 0;
         list_for_each_entry(datagram, &master->datagram_queue, queue) {
-            if (datagram->state == EC_CMD_SENT
+            if (datagram->state == EC_DATAGRAM_SENT
                 && datagram->type == datagram_type
                 && datagram->index == datagram_index
                 && datagram->data_size == data_size) {
@@ -480,7 +479,7 @@
         cur_data += EC_DATAGRAM_FOOTER_SIZE;
 
         // dequeue the received datagram
-        datagram->state = EC_CMD_RECEIVED;
+        datagram->state = EC_DATAGRAM_RECEIVED;
         list_del_init(&datagram->queue);
     }
 }
@@ -488,50 +487,6 @@
 /*****************************************************************************/
 
 /**
-   Sends a single datagram and waits for its reception.
-   If the slave doesn't respond, the datagram is sent again.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_master_simple_io(ec_master_t *master, /**< EtherCAT master */
-                        ec_datagram_t *datagram /**< datagram */
-                        )
-{
-    unsigned int response_tries_left;
-
-    response_tries_left = 10000;
-
-    while (1)
-    {
-        ec_master_queue_datagram(master, datagram);
-        ecrt_master_sync_io(master);
-
-        if (datagram->state == EC_CMD_RECEIVED) {
-            if (likely(datagram->working_counter))
-                return 0;
-        }
-        else if (datagram->state == EC_CMD_TIMEOUT) {
-            EC_ERR("Simple-IO TIMEOUT!\n");
-            return -1;
-        }
-        else if (datagram->state == EC_CMD_ERROR) {
-            EC_ERR("Simple-IO datagram error!\n");
-            return -1;
-        }
-
-        // no direct response, wait a little bit...
-        udelay(100);
-
-        if (unlikely(--response_tries_left)) {
-            EC_ERR("No response in simple-IO!\n");
-            return -1;
-        }
-    }
-}
-
-/*****************************************************************************/
-
-/**
    Scans the EtherCAT bus for slaves.
    Creates a list of slave structures for further processing.
    \return 0 in case of success, else < 0
@@ -539,102 +494,22 @@
 
 int ec_master_bus_scan(ec_master_t *master /**< EtherCAT master */)
 {
-    ec_slave_t *slave;
-    ec_slave_ident_t *ident;
-    ec_datagram_t *datagram;
-    unsigned int i;
-    uint16_t coupler_index, coupler_subindex;
-    uint16_t reverse_coupler_index, current_coupler_index;
-
-    if (!list_empty(&master->slaves)) {
-        EC_ERR("Slave scan already done!\n");
+    ec_fsm_t *fsm = &master->fsm;
+
+    ec_fsm_startup(fsm); // init startup state machine
+
+    do {
+        ec_fsm_execute(fsm);
+        ec_master_sync_io(master);
+    }
+    while (ec_fsm_startup_running(fsm));
+
+    if (!ec_fsm_startup_success(fsm)) {
+        ec_master_clear_slaves(master);
         return -1;
     }
 
-    datagram = &master->simple_datagram;
-
-    // determine number of slaves on bus
-    if (ec_datagram_brd(datagram, 0x0000, 4)) return -1;
-    if (unlikely(ec_master_simple_io(master, datagram))) return -1;
-    master->slave_count = datagram->working_counter;
-    EC_INFO("Found %i slaves on bus.\n", master->slave_count);
-
-    if (!master->slave_count) return 0;
-
-    // init slaves
-    for (i = 0; i < master->slave_count; i++) {
-        if (!(slave =
-              (ec_slave_t *) kmalloc(sizeof(ec_slave_t), GFP_KERNEL))) {
-            EC_ERR("Failed to allocate slave %i!\n", i);
-            goto out_free;
-        }
-
-        if (ec_slave_init(slave, master, i, i + 1)) goto out_free;
-
-        if (kobject_add(&slave->kobj)) {
-            EC_ERR("Failed to add kobject.\n");
-            kobject_put(&slave->kobj); // free
-            goto out_free;
-        }
-
-        list_add_tail(&slave->list, &master->slaves);
-    }
-
-    coupler_index = 0;
-    reverse_coupler_index = 0xFFFF;
-    current_coupler_index = 0x3FFF;
-    coupler_subindex = 0;
-
-    // for every slave on the bus
-    list_for_each_entry(slave, &master->slaves, list) {
-
-        // write station address
-        if (ec_datagram_apwr(datagram, slave->ring_position, 0x0010,
-                            sizeof(uint16_t))) goto out_free;
-        EC_WRITE_U16(datagram->data, slave->station_address);
-        if (unlikely(ec_master_simple_io(master, datagram))) {
-            EC_ERR("Writing station address failed on slave %i!\n",
-                   slave->ring_position);
-            goto out_free;
-        }
-
-        // fetch all slave information
-        if (ec_slave_fetch(slave)) goto out_free;
-
-        // search for identification in "database"
-        ident = slave_idents;
-        while (ident->type) {
-            if (unlikely(ident->vendor_id == slave->sii_vendor_id
-                         && ident->product_code == slave->sii_product_code)) {
-                slave->type = ident->type;
-                break;
-            }
-            ident++;
-        }
-
-        if (!slave->type) {
-            EC_WARN("Unknown slave device (vendor 0x%08X, code 0x%08X) at"
-                    " position %i.\n", slave->sii_vendor_id,
-                    slave->sii_product_code, slave->ring_position);
-        }
-        else if (slave->type->special == EC_TYPE_BUS_COUPLER) {
-            if (slave->sii_alias)
-                current_coupler_index = reverse_coupler_index--;
-            else
-                current_coupler_index = coupler_index++;
-            coupler_subindex = 0;
-        }
-
-        slave->coupler_index = current_coupler_index;
-        slave->coupler_subindex = coupler_subindex;
-        coupler_subindex++;
-    }
-
     return 0;
-
- out_free:
-    ec_master_clear_slaves(master);
-    return -1;
 }
 
 /*****************************************************************************/
@@ -673,41 +548,43 @@
 /*****************************************************************************/
 
 /**
-   Starts the Free-Run mode.
-*/
-
-void ec_master_freerun_start(ec_master_t *master /**< EtherCAT master */)
-{
-    if (master->mode == EC_MASTER_MODE_FREERUN) return;
-
-    if (master->mode == EC_MASTER_MODE_RUNNING) {
-        EC_ERR("ec_master_freerun_start: Master already running!\n");
+   Starts the Idle mode.
+*/
+
+void ec_master_idle_start(ec_master_t *master /**< EtherCAT master */)
+{
+    if (master->mode == EC_MASTER_MODE_IDLE) return;
+
+    if (master->mode == EC_MASTER_MODE_OPERATION) {
+        EC_ERR("ec_master_idle_start: Master already running!\n");
         return;
     }
 
-    EC_INFO("Starting Free-Run mode.\n");
-
-    master->mode = EC_MASTER_MODE_FREERUN;
+    EC_INFO("Starting Idle mode.\n");
+
+    master->mode = EC_MASTER_MODE_IDLE;
     ec_fsm_reset(&master->fsm);
-    queue_delayed_work(master->workqueue, &master->freerun_work, 1);
-}
-
-/*****************************************************************************/
-
-/**
-   Stops the Free-Run mode.
-*/
-
-void ec_master_freerun_stop(ec_master_t *master /**< EtherCAT master */)
-{
-    if (master->mode != EC_MASTER_MODE_FREERUN) return;
+    queue_delayed_work(master->workqueue, &master->idle_work, 1);
+}
+
+/*****************************************************************************/
+
+/**
+   Stops the Idle mode.
+*/
+
+void ec_master_idle_stop(ec_master_t *master /**< EtherCAT master */)
+{
+    if (master->mode != EC_MASTER_MODE_IDLE) return;
 
     ec_master_eoe_stop(master);
 
-    EC_INFO("Stopping Free-Run mode.\n");
-    master->mode = EC_MASTER_MODE_IDLE;
-
-    if (!cancel_delayed_work(&master->freerun_work)) {
+    EC_INFO("Stopping Idle mode.\n");
+    master->mode = EC_MASTER_MODE_ORPHANED; // this is important for the
+                                            // IDLE work function to not
+                                            // queue itself again
+
+    if (!cancel_delayed_work(&master->idle_work)) {
         flush_workqueue(master->workqueue);
     }
 
@@ -717,38 +594,38 @@
 /*****************************************************************************/
 
 /**
-   Free-Run mode function.
-*/
-
-void ec_master_freerun(void *data /**< master pointer */)
+   Idle mode function.
+*/
+
+void ec_master_idle_run(void *data /**< master pointer */)
 {
     ec_master_t *master = (ec_master_t *) data;
 
     // aquire master lock
     spin_lock_bh(&master->internal_lock);
 
-    ecrt_master_async_receive(master);
+    ecrt_master_receive(master);
 
     // execute master state machine
     ec_fsm_execute(&master->fsm);
 
-    ecrt_master_async_send(master);
+    ecrt_master_send(master);
 
     // release master lock
     spin_unlock_bh(&master->internal_lock);
 
-    if (master->mode == EC_MASTER_MODE_FREERUN)
-        queue_delayed_work(master->workqueue, &master->freerun_work, 1);
-}
-
-/*****************************************************************************/
-
-/**
-   Initializes a sync manager configuration page.
+    if (master->mode == EC_MASTER_MODE_IDLE)
+        queue_delayed_work(master->workqueue, &master->idle_work, 1);
+}
+
+/*****************************************************************************/
+
+/**
+   Initializes a sync manager configuration page with EEPROM data.
    The referenced memory (\a data) must be at least EC_SYNC_SIZE bytes.
 */
 
-void ec_sync_config(const ec_sync_t *sync, /**< sync manager */
+void ec_sync_config(const ec_sii_sync_t *sync, /**< sync manager */
                     const ec_slave_t *slave, /**< EtherCAT slave */
                     uint8_t *data /**> configuration memory */
                     )
@@ -757,26 +634,16 @@
 
     sync_size = ec_slave_calc_sync_size(slave, sync);
 
+    if (slave->master->debug_level) {
+        EC_INFO("Slave %i, sync manager %i:\n", slave->ring_position,
+                sync->index);
+        EC_INFO("  Address: 0x%04X\n", sync->physical_start_address);
+        EC_INFO("     Size: %i\n", sync_size);
+        EC_INFO("  Control: 0x%02X\n", sync->control_register);
+    }
+
     EC_WRITE_U16(data,     sync->physical_start_address);
     EC_WRITE_U16(data + 2, sync_size);
-    EC_WRITE_U8 (data + 4, sync->control_byte);
-    EC_WRITE_U8 (data + 5, 0x00); // status byte (read only)
-    EC_WRITE_U16(data + 6, 0x0001); // enable
-}
-
-/*****************************************************************************/
-
-/**
-   Initializes a sync manager configuration page with EEPROM data.
-   The referenced memory (\a data) must be at least EC_SYNC_SIZE bytes.
-*/
-
-void ec_eeprom_sync_config(const ec_eeprom_sync_t *sync, /**< sync manager */
-                           uint8_t *data /**> configuration memory */
-                           )
-{
-    EC_WRITE_U16(data,     sync->physical_start_address);
-    EC_WRITE_U16(data + 2, sync->length);
     EC_WRITE_U8 (data + 4, sync->control_register);
     EC_WRITE_U8 (data + 5, 0x00); // status byte (read only)
     EC_WRITE_U16(data + 6, sync->enable ? 0x0001 : 0x0000); // enable
@@ -804,7 +671,8 @@
     EC_WRITE_U8 (data + 7,  0x07); // logical end bit
     EC_WRITE_U16(data + 8,  fmmu->sync->physical_start_address);
     EC_WRITE_U8 (data + 10, 0x00); // physical start bit
-    EC_WRITE_U8 (data + 11, (fmmu->sync->control_byte & 0x04) ? 0x02 : 0x01);
+    EC_WRITE_U8 (data + 11, ((fmmu->sync->control_register & 0x04)
+                             ? 0x02 : 0x01));
     EC_WRITE_U16(data + 12, 0x0001); // enable
     EC_WRITE_U16(data + 14, 0x0000); // reserved
 }
@@ -828,13 +696,19 @@
     }
     else if (attr == &attr_mode) {
         switch (master->mode) {
+            case EC_MASTER_MODE_ORPHANED:
+                return sprintf(buffer, "ORPHANED\n");
             case EC_MASTER_MODE_IDLE:
                 return sprintf(buffer, "IDLE\n");
-            case EC_MASTER_MODE_FREERUN:
-                return sprintf(buffer, "FREERUN\n");
-            case EC_MASTER_MODE_RUNNING:
-                return sprintf(buffer, "RUNNING\n");
-        }
+            case EC_MASTER_MODE_OPERATION:
+                return sprintf(buffer, "OPERATION\n");
+        }
+    }
+    else if (attr == &attr_debug_level) {
+        return sprintf(buffer, "%i\n", master->debug_level);
+    }
+    else if (attr == &attr_eeprom_write_enable) {
+        return sprintf(buffer, "%i\n", master->eeprom_write_enable);
     }
 
     return 0;
@@ -874,6 +748,24 @@
             EC_INFO("Slave EEPROM writing disabled.\n");
         }
     }
+    else if (attr == &attr_debug_level) {
+        if (!strcmp(buffer, "0\n")) {
+            master->debug_level = 0;
+        }
+        else if (!strcmp(buffer, "1\n")) {
+            master->debug_level = 1;
+        }
+        else if (!strcmp(buffer, "2\n")) {
+            master->debug_level = 2;
+        }
+        else {
+            EC_ERR("Invalid debug level value!\n");
+            return -EINVAL;
+        }
+
+        EC_INFO("Master debug level set to %i.\n", master->debug_level);
+        return size;
+    }
 
     return -EINVAL;
 }
@@ -881,7 +773,7 @@
 /*****************************************************************************/
 
 /**
-   Starts Ethernet-over-EtherCAT processing for all EoE-capable slaves.
+   Starts/Stops Ethernet-over-EtherCAT processing on demand.
 */
 
 void ec_master_eoe_start(ec_master_t *master /**< EtherCAT master */)
@@ -892,12 +784,17 @@
 
     if (master->eoe_running) return;
 
+    // if the locking callbacks are not set in operation mode,
+    // the EoE timer my not be started.
+    if (master->mode == EC_MASTER_MODE_OPERATION
+        && (!master->request_cb || !master->release_cb)) return;
+
     // decouple all EoE handlers
     list_for_each_entry(eoe, &master->eoe_handlers, list)
         eoe->slave = NULL;
+
+    // couple a free EoE handler to every EoE-capable slave
     coupled = 0;
-
-    // couple a free EoE handler to every EoE-capable slave
     list_for_each_entry(slave, &master->slaves, list) {
         if (!(slave->sii_mailbox_protocols & EC_MBOX_EOE)) continue;
 
@@ -909,12 +806,8 @@
             coupled++;
             EC_INFO("Coupling device %s to slave %i.\n",
                     eoe->dev->name, slave->ring_position);
-            if (eoe->opened) {
-                slave->requested_state = EC_SLAVE_STATE_OP;
-            }
-            else {
-                slave->requested_state = EC_SLAVE_STATE_INIT;
-            }
+            if (eoe->opened) slave->requested_state = EC_SLAVE_STATE_OP;
+            else slave->requested_state = EC_SLAVE_STATE_INIT;
             slave->error_flag = 0;
             break;
         }
@@ -985,29 +878,29 @@
     if (!active) goto queue_timer;
 
     // aquire master lock...
-    if (master->mode == EC_MASTER_MODE_RUNNING) {
+    if (master->mode == EC_MASTER_MODE_OPERATION) {
         // request_cb must return 0, if the lock has been aquired!
         if (master->request_cb(master->cb_data))
             goto queue_timer;
     }
-    else if (master->mode == EC_MASTER_MODE_FREERUN) {
+    else if (master->mode == EC_MASTER_MODE_IDLE) {
         spin_lock(&master->internal_lock);
     }
     else
         goto queue_timer;
 
     // actual EoE stuff
-    ecrt_master_async_receive(master);
+    ecrt_master_receive(master);
     list_for_each_entry(eoe, &master->eoe_handlers, list) {
         ec_eoe_run(eoe);
     }
-    ecrt_master_async_send(master);
+    ecrt_master_send(master);
 
     // release lock...
-    if (master->mode == EC_MASTER_MODE_RUNNING) {
+    if (master->mode == EC_MASTER_MODE_OPERATION) {
         master->release_cb(master->cb_data);
     }
-    else if (master->mode == EC_MASTER_MODE_FREERUN) {
+    else if (master->mode == EC_MASTER_MODE_IDLE) {
         spin_unlock(&master->internal_lock);
     }
 
@@ -1016,6 +909,38 @@
     add_timer(&master->eoe_timer);
 }
 
+/*****************************************************************************/
+
+/**
+   Calculates Advanced Position Adresses.
+*/
+
+void ec_master_calc_addressing(ec_master_t *master /**< EtherCAT master */)
+{
+    uint16_t coupler_index, coupler_subindex;
+    uint16_t reverse_coupler_index, current_coupler_index;
+    ec_slave_t *slave;
+
+    coupler_index = 0;
+    reverse_coupler_index = 0xFFFF;
+    current_coupler_index = 0x0000;
+    coupler_subindex = 0;
+
+    list_for_each_entry(slave, &master->slaves, list) {
+        if (ec_slave_is_coupler(slave)) {
+            if (slave->sii_alias)
+                current_coupler_index = reverse_coupler_index--;
+            else
+                current_coupler_index = coupler_index++;
+            coupler_subindex = 0;
+        }
+
+        slave->coupler_index = current_coupler_index;
+        slave->coupler_subindex = coupler_subindex;
+        coupler_subindex++;
+    }
+}
+
 /******************************************************************************
  *  Realtime interface
  *****************************************************************************/
@@ -1074,17 +999,10 @@
 
 int ecrt_master_activate(ec_master_t *master /**< EtherCAT master */)
 {
-    unsigned int j;
-    ec_slave_t *slave;
-    ec_datagram_t *datagram;
-    const ec_sync_t *sync;
-    const ec_slave_type_t *type;
-    const ec_fmmu_t *fmmu;
     uint32_t domain_offset;
     ec_domain_t *domain;
-    ec_eeprom_sync_t *eeprom_sync, mbox_sync;
-
-    datagram = &master->simple_datagram;
+    ec_fsm_t *fsm = &master->fsm;
+    ec_slave_t *slave;
 
     // allocate all domains
     domain_offset = 0;
@@ -1096,149 +1014,29 @@
         domain_offset += domain->data_size;
     }
 
-    // configure and activate slaves
+    // determine initial states.
     list_for_each_entry(slave, &master->slaves, list) {
-
-        // change state to INIT
-        if (unlikely(ec_slave_state_change(slave, EC_SLAVE_STATE_INIT)))
-            return -1;
-
-        // check for slave registration
-        type = slave->type;
-        if (!type)
-            EC_WARN("Slave %i has unknown type!\n", slave->ring_position);
-
-        // check and reset CRC fault counters
-        ec_slave_check_crc(slave);
-
-        // reset FMMUs
-        if (slave->base_fmmu_count) {
-            if (ec_datagram_npwr(datagram, slave->station_address, 0x0600,
-                                 EC_FMMU_SIZE * slave->base_fmmu_count))
-                return -1;
-            memset(datagram->data, 0x00,
-                   EC_FMMU_SIZE * slave->base_fmmu_count);
-            if (unlikely(ec_master_simple_io(master, datagram))) {
-                EC_ERR("Resetting FMMUs failed on slave %i!\n",
-                       slave->ring_position);
-                return -1;
-            }
-        }
-
-        // reset sync managers
-        if (slave->base_sync_count) {
-            if (ec_datagram_npwr(datagram, slave->station_address, 0x0800,
-                                EC_SYNC_SIZE * slave->base_sync_count))
-                return -1;
-            memset(datagram->data, 0x00, EC_SYNC_SIZE * slave->base_sync_count);
-            if (unlikely(ec_master_simple_io(master, datagram))) {
-                EC_ERR("Resetting sync managers failed on slave %i!\n",
-                       slave->ring_position);
-                return -1;
-            }
-        }
-
-        // configure sync managers
-        if (type) { // known slave type, take type's SM information
-            for (j = 0; type->sync_managers[j] && j < EC_MAX_SYNC; j++) {
-                sync = type->sync_managers[j];
-                if (ec_datagram_npwr(datagram, slave->station_address,
-                                    0x0800 + j * EC_SYNC_SIZE, EC_SYNC_SIZE))
-                    return -1;
-                ec_sync_config(sync, slave, datagram->data);
-                if (unlikely(ec_master_simple_io(master, datagram))) {
-                    EC_ERR("Setting sync manager %i failed on slave %i!\n",
-                           j, slave->ring_position);
-                    return -1;
-                }
-            }
-        }
-        else if (slave->sii_mailbox_protocols) { // unknown type, but mailbox
-            // does the device supply SM configurations in its EEPROM?
-	    if (!list_empty(&slave->eeprom_syncs)) {
-		list_for_each_entry(eeprom_sync, &slave->eeprom_syncs, list) {
-		    EC_INFO("Sync manager %i...\n", eeprom_sync->index);
-		    if (ec_datagram_npwr(datagram, slave->station_address,
-                                 0x800 + eeprom_sync->index *
-                                 EC_SYNC_SIZE,
-                                 EC_SYNC_SIZE)) return -1;
-		    ec_eeprom_sync_config(eeprom_sync, datagram->data);
-		    if (unlikely(ec_master_simple_io(master, datagram))) {
-			EC_ERR("Setting sync manager %i failed on slave %i!\n",
-			       eeprom_sync->index, slave->ring_position);
-			return -1;
-		    }
-		}
-            }
-	    else { // no sync manager information; guess mailbox settings
-		mbox_sync.physical_start_address =
-                    slave->sii_rx_mailbox_offset;
-		mbox_sync.length = slave->sii_rx_mailbox_size;
-		mbox_sync.control_register = 0x26;
-		mbox_sync.enable = 1;
-		if (ec_datagram_npwr(datagram, slave->station_address,
-                             0x800,EC_SYNC_SIZE)) return -1;
-		ec_eeprom_sync_config(&mbox_sync, datagram->data);
-		if (unlikely(ec_master_simple_io(master, datagram))) {
-		    EC_ERR("Setting sync manager 0 failed on slave %i!\n",
-			   slave->ring_position);
-		    return -1;
-		}
-
-		mbox_sync.physical_start_address =
-                    slave->sii_tx_mailbox_offset;
-		mbox_sync.length = slave->sii_tx_mailbox_size;
-		mbox_sync.control_register = 0x22;
-		mbox_sync.enable = 1;
-		if (ec_datagram_npwr(datagram, slave->station_address,
-                             0x808, EC_SYNC_SIZE)) return -1;
-		ec_eeprom_sync_config(&mbox_sync, datagram->data);
-		if (unlikely(ec_master_simple_io(master, datagram))) {
-		    EC_ERR("Setting sync manager 1 failed on slave %i!\n",
-			   slave->ring_position);
-		    return -1;
-		}
-	    }
-	    EC_INFO("Mailbox configured for unknown slave %i\n",
-		    slave->ring_position);
-        }
-
-        // change state to PREOP
-        if (unlikely(ec_slave_state_change(slave, EC_SLAVE_STATE_PREOP)))
-            return -1;
-
-        // stop activation here for slaves without type
-        if (!type) continue;
-
-        // slaves that are not registered are only brought into PREOP
-        // state -> nice blinking and mailbox communication possible
-        if (!slave->registered && !slave->type->special) {
-            EC_WARN("Slave %i was not registered!\n", slave->ring_position);
-            continue;
-        }
-
-        // configure FMMUs
-        for (j = 0; j < slave->fmmu_count; j++) {
-            fmmu = &slave->fmmus[j];
-            if (ec_datagram_npwr(datagram, slave->station_address,
-                                 0x0600 + j * EC_FMMU_SIZE, EC_FMMU_SIZE))
-                return -1;
-            ec_fmmu_config(fmmu, slave, datagram->data);
-            if (unlikely(ec_master_simple_io(master, datagram))) {
-                EC_ERR("Setting FMMU %i failed on slave %i!\n",
-                       j, slave->ring_position);
-                return -1;
-            }
-        }
-
-        // change state to SAVEOP
-        if (unlikely(ec_slave_state_change(slave, EC_SLAVE_STATE_SAVEOP)))
-            return -1;
-
-        // change state to OP
-        if (unlikely(ec_slave_state_change(slave, EC_SLAVE_STATE_OP)))
-            return -1;
-    }
+        if (ec_slave_is_coupler(slave) || slave->registered) {
+            slave->requested_state = EC_SLAVE_STATE_OP;
+        }
+        else {
+            slave->requested_state = EC_SLAVE_STATE_PREOP;
+        }
+    }
+
+    ec_fsm_configuration(fsm); // init configuration state machine
+
+    do {
+        ec_fsm_execute(fsm);
+        ec_master_sync_io(master);
+    }
+    while (ec_fsm_configuration_running(fsm));
+
+    if (!ec_fsm_configuration_success(fsm)) {
+        return -1;
+    }
+
+    ec_fsm_reset(&master->fsm); // prepare for operation state machine
 
     return 0;
 }
@@ -1252,59 +1050,39 @@
 
 void ecrt_master_deactivate(ec_master_t *master /**< EtherCAT master */)
 {
+    ec_fsm_t *fsm = &master->fsm;
     ec_slave_t *slave;
 
     list_for_each_entry(slave, &master->slaves, list) {
-        ec_slave_check_crc(slave);
-        ec_slave_state_change(slave, EC_SLAVE_STATE_INIT);
-    }
-}
-
-
-/*****************************************************************************/
-
-/**
-   Fetches the SDO dictionaries of all slaves.
-   Slaves that do not support the CoE protocol are left out.
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_master_fetch_sdo_lists(ec_master_t *master /**< EtherCAT master */)
-{
-    ec_slave_t *slave;
-
-    list_for_each_entry(slave, &master->slaves, list) {
-        if (slave->sii_mailbox_protocols & EC_MBOX_COE) {
-            if (unlikely(ec_slave_fetch_sdo_list(slave))) {
-                EC_ERR("Failed to fetch SDO list on slave %i!\n",
-                       slave->ring_position);
-                return -1;
-            }
-        }
-    }
-
-    return 0;
+        slave->requested_state = EC_SLAVE_STATE_INIT;
+    }
+
+    ec_fsm_configuration(fsm); // init configuration state machine
+
+    do {
+        ec_fsm_execute(fsm);
+        ec_master_sync_io(master);
+    }
+    while (ec_fsm_configuration_running(fsm));
 }
 
 /*****************************************************************************/
 
 /**
    Sends queued datagrams and waits for their reception.
-   \ingroup RealtimeInterface
-*/
-
-void ecrt_master_sync_io(ec_master_t *master /**< EtherCAT master */)
+*/
+
+void ec_master_sync_io(ec_master_t *master /**< EtherCAT master */)
 {
     ec_datagram_t *datagram, *n;
     unsigned int datagrams_sent;
     cycles_t t_start, t_end, t_timeout;
 
     // send datagrams
-    ecrt_master_async_send(master);
+    ecrt_master_send(master);
 
     t_start = get_cycles(); // measure io time
-    t_timeout = (cycles_t) master->timeout * (cpu_khz / 1000);
+    t_timeout = (cycles_t) EC_IO_TIMEOUT * (cpu_khz / 1000);
 
     while (1) { // active waiting
         ec_device_call_isr(master->device);
@@ -1314,9 +1092,9 @@
 
         datagrams_sent = 0;
         list_for_each_entry_safe(datagram, n, &master->datagram_queue, queue) {
-            if (datagram->state == EC_CMD_RECEIVED)
+            if (datagram->state == EC_DATAGRAM_RECEIVED)
                 list_del_init(&datagram->queue);
-            else if (datagram->state == EC_CMD_SENT)
+            else if (datagram->state == EC_DATAGRAM_SENT)
                 datagrams_sent++;
         }
 
@@ -1326,13 +1104,13 @@
     // timeout; dequeue all datagrams
     list_for_each_entry_safe(datagram, n, &master->datagram_queue, queue) {
         switch (datagram->state) {
-            case EC_CMD_SENT:
-            case EC_CMD_QUEUED:
-                datagram->state = EC_CMD_TIMEOUT;
+            case EC_DATAGRAM_SENT:
+            case EC_DATAGRAM_QUEUED:
+                datagram->state = EC_DATAGRAM_TIMED_OUT;
                 master->stats.timeouts++;
                 ec_master_output_stats(master);
                 break;
-            case EC_CMD_RECEIVED:
+            case EC_DATAGRAM_RECEIVED:
                 master->stats.delayed++;
                 ec_master_output_stats(master);
                 break;
@@ -1350,14 +1128,14 @@
    \ingroup RealtimeInterface
 */
 
-void ecrt_master_async_send(ec_master_t *master /**< EtherCAT master */)
+void ecrt_master_send(ec_master_t *master /**< EtherCAT master */)
 {
     ec_datagram_t *datagram, *n;
 
     if (unlikely(!master->device->link_state)) {
         // link is down, no datagram can be sent
         list_for_each_entry_safe(datagram, n, &master->datagram_queue, queue) {
-            datagram->state = EC_CMD_ERROR;
+            datagram->state = EC_DATAGRAM_ERROR;
             list_del_init(&datagram->queue);
         }
 
@@ -1377,7 +1155,7 @@
    \ingroup RealtimeInterface
 */
 
-void ecrt_master_async_receive(ec_master_t *master /**< EtherCAT master */)
+void ecrt_master_receive(ec_master_t *master /**< EtherCAT master */)
 {
     ec_datagram_t *datagram, *next;
     cycles_t t_received, t_timeout;
@@ -1385,21 +1163,21 @@
     ec_device_call_isr(master->device);
 
     t_received = get_cycles();
-    t_timeout = (cycles_t) master->timeout * (cpu_khz / 1000);
+    t_timeout = (cycles_t) EC_IO_TIMEOUT * (cpu_khz / 1000);
 
     // dequeue all received datagrams
     list_for_each_entry_safe(datagram, next, &master->datagram_queue, queue)
-        if (datagram->state == EC_CMD_RECEIVED)
+        if (datagram->state == EC_DATAGRAM_RECEIVED)
             list_del_init(&datagram->queue);
 
     // dequeue all datagrams that timed out
     list_for_each_entry_safe(datagram, next, &master->datagram_queue, queue) {
         switch (datagram->state) {
-            case EC_CMD_SENT:
-            case EC_CMD_QUEUED:
+            case EC_DATAGRAM_SENT:
+            case EC_DATAGRAM_QUEUED:
                 if (t_received - datagram->t_sent > t_timeout) {
                     list_del_init(&datagram->queue);
-                    datagram->state = EC_CMD_TIMEOUT;
+                    datagram->state = EC_DATAGRAM_TIMED_OUT;
                     master->stats.timeouts++;
                     ec_master_output_stats(master);
                 }
@@ -1415,23 +1193,23 @@
 /**
    Prepares synchronous IO.
    Queues all domain datagrams and sends them. Then waits a certain time, so
-   that ecrt_master_sasync_receive() can be called securely.
+   that ecrt_master_receive() can be called securely.
    \ingroup RealtimeInterface
 */
 
-void ecrt_master_prepare_async_io(ec_master_t *master /**< EtherCAT master */)
+void ecrt_master_prepare(ec_master_t *master /**< EtherCAT master */)
 {
     ec_domain_t *domain;
     cycles_t t_start, t_end, t_timeout;
 
     // queue datagrams of all domains
     list_for_each_entry(domain, &master->domains, list)
-        ecrt_domain_queue(domain);
-
-    ecrt_master_async_send(master);
+        ec_domain_queue(domain);
+
+    ecrt_master_send(master);
 
     t_start = get_cycles(); // take sending time
-    t_timeout = (cycles_t) master->timeout * (cpu_khz / 1000);
+    t_timeout = (cycles_t) EC_IO_TIMEOUT * (cpu_khz / 1000);
 
     // active waiting
     while (1) {
@@ -1535,8 +1313,7 @@
         }
 
         if (alias_requested) {
-            if (!alias_slave->type ||
-                alias_slave->type->special != EC_TYPE_BUS_COUPLER) {
+            if (!ec_slave_is_coupler(alias_slave)) {
                 EC_ERR("Slave address \"%s\": Alias slave must be bus coupler"
                        " in colon mode.\n", address);
                 return NULL;
@@ -1587,92 +1364,16 @@
 
 /*****************************************************************************/
 
-/**
-   Starts Ethernet-over-EtherCAT processing for all EoE-capable slaves.
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_master_start_eoe(ec_master_t *master /**< EtherCAT master */)
-{
-    if (!master->request_cb || !master->release_cb) {
-        EC_ERR("EoE requires master callbacks to be set!\n");
-        return -1;
-    }
-
-    ec_master_eoe_start(master);
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Sets the debug level of the master.
-   The following levels are valid:
-   - 1: only output positions marks and basic data
-   - 2: additional frame data output
-   \ingroup RealtimeInterface
-*/
-
-void ecrt_master_debug(ec_master_t *master, /**< EtherCAT master */
-                       int level /**< debug level */
-                       )
-{
-    if (level != master->debug_level) {
-        master->debug_level = level;
-        EC_INFO("Master debug level set to %i.\n", level);
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   Outputs all master information.
-   Verbosity:
-   - 0: Only slave types and positions
-   - 1: with EEPROM contents
-   - >1: with SDO dictionaries
-   \ingroup RealtimeInterface
-*/
-
-void ecrt_master_print(const ec_master_t *master, /**< EtherCAT master */
-                       unsigned int verbosity /**< verbosity level */
-                       )
-{
-    ec_slave_t *slave;
-    ec_eoe_t *eoe;
-
-    EC_INFO("*** Begin master information ***\n");
-    if (master->slave_count) {
-        EC_INFO("Slave list:\n");
-        list_for_each_entry(slave, &master->slaves, list)
-            ec_slave_print(slave, verbosity);
-    }
-    if (!list_empty(&master->eoe_handlers)) {
-        EC_INFO("Ethernet-over-EtherCAT (EoE) objects:\n");
-        list_for_each_entry(eoe, &master->eoe_handlers, list) {
-            ec_eoe_print(eoe);
-        }
-    }
-    EC_INFO("*** End master information ***\n");
-}
-
-/*****************************************************************************/
-
 /** \cond */
 
 EXPORT_SYMBOL(ecrt_master_create_domain);
 EXPORT_SYMBOL(ecrt_master_activate);
 EXPORT_SYMBOL(ecrt_master_deactivate);
-EXPORT_SYMBOL(ecrt_master_fetch_sdo_lists);
-EXPORT_SYMBOL(ecrt_master_prepare_async_io);
-EXPORT_SYMBOL(ecrt_master_sync_io);
-EXPORT_SYMBOL(ecrt_master_async_send);
-EXPORT_SYMBOL(ecrt_master_async_receive);
+EXPORT_SYMBOL(ecrt_master_prepare);
+EXPORT_SYMBOL(ecrt_master_send);
+EXPORT_SYMBOL(ecrt_master_receive);
 EXPORT_SYMBOL(ecrt_master_run);
 EXPORT_SYMBOL(ecrt_master_callbacks);
-EXPORT_SYMBOL(ecrt_master_start_eoe);
-EXPORT_SYMBOL(ecrt_master_debug);
-EXPORT_SYMBOL(ecrt_master_print);
 EXPORT_SYMBOL(ecrt_master_get_slave);
 
 /** \endcond */
--- a/master/master.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/master.h	Thu Aug 03 12:59:01 2006 +0000
@@ -57,9 +57,9 @@
 
 typedef enum
 {
+    EC_MASTER_MODE_ORPHANED,
     EC_MASTER_MODE_IDLE,
-    EC_MASTER_MODE_FREERUN,
-    EC_MASTER_MODE_RUNNING
+    EC_MASTER_MODE_OPERATION
 }
 ec_master_mode_t;
 
@@ -104,21 +104,18 @@
 
     struct list_head domains; /**< list of domains */
 
-    ec_datagram_t simple_datagram; /**< datagram structure for initialization */
-    unsigned int timeout; /**< timeout in synchronous IO */
-
     int debug_level; /**< master debug level */
     ec_stats_t stats; /**< cyclic statistics */
 
     struct workqueue_struct *workqueue; /**< master workqueue */
-    struct work_struct freerun_work; /**< free run work object */
+    struct work_struct idle_work; /**< free run work object */
     ec_fsm_t fsm; /**< master state machine */
     ec_master_mode_t mode; /**< master mode */
 
     struct timer_list eoe_timer; /**< EoE timer object */
     unsigned int eoe_running; /**< non-zero, if EoE processing is active. */
     struct list_head eoe_handlers; /**< Ethernet-over-EtherCAT handlers */
-    spinlock_t internal_lock; /**< spinlock used in freerun mode */
+    spinlock_t internal_lock; /**< spinlock used in idle mode */
     int (*request_cb)(void *); /**< lock request callback */
     void (*release_cb)(void *); /**< lock release callback */
     void *cb_data; /**< data parameter of locking callbacks */
@@ -134,8 +131,8 @@
 void ec_master_reset(ec_master_t *);
 
 // free run
-void ec_master_freerun_start(ec_master_t *);
-void ec_master_freerun_stop(ec_master_t *);
+void ec_master_idle_start(ec_master_t *);
+void ec_master_idle_stop(ec_master_t *);
 
 // EoE
 void ec_master_eoe_start(ec_master_t *);
@@ -144,17 +141,18 @@
 // IO
 void ec_master_receive(ec_master_t *, const uint8_t *, size_t);
 void ec_master_queue_datagram(ec_master_t *, ec_datagram_t *);
-int ec_master_simple_io(ec_master_t *, ec_datagram_t *);
 
 // slave management
 int ec_master_bus_scan(ec_master_t *);
 
 // misc.
+void ec_master_output_stats(ec_master_t *);
 void ec_master_clear_slaves(ec_master_t *);
-void ec_sync_config(const ec_sync_t *, const ec_slave_t *, uint8_t *);
-void ec_eeprom_sync_config(const ec_eeprom_sync_t *, uint8_t *);
+
+// other methods
+void ec_sync_config(const ec_sii_sync_t *, const ec_slave_t *, uint8_t *);
 void ec_fmmu_config(const ec_fmmu_t *, const ec_slave_t *, uint8_t *);
-void ec_master_output_stats(ec_master_t *);
+void ec_master_calc_addressing(ec_master_t *);
 
 /*****************************************************************************/
 
--- a/master/module.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/module.c	Thu Aug 03 12:59:01 2006 +0000
@@ -67,7 +67,7 @@
 /*****************************************************************************/
 
 static int ec_master_count = 1; /**< parameter value, number of masters */
-static int ec_eoe_devices = 0; /**< parameter value, number of EoE interf. */
+static int ec_eoeif_count = 0; /**< parameter value, number of EoE interf. */
 static struct list_head ec_masters; /**< list of masters */
 
 /*****************************************************************************/
@@ -75,14 +75,14 @@
 /** \cond */
 
 module_param(ec_master_count, int, S_IRUGO);
-module_param(ec_eoe_devices, int, S_IRUGO);
+module_param(ec_eoeif_count, int, S_IRUGO);
 
 MODULE_AUTHOR("Florian Pose <fp@igh-essen.com>");
 MODULE_DESCRIPTION("EtherCAT master driver module");
 MODULE_LICENSE("GPL");
 MODULE_VERSION(COMPILE_INFO);
 MODULE_PARM_DESC(ec_master_count, "number of EtherCAT masters to initialize");
-MODULE_PARM_DESC(ec_eoe_devices, "number of EoE devices per master");
+MODULE_PARM_DESC(ec_eoeif_count, "number of EoE interfaces per master");
 
 /** \endcond */
 
@@ -117,7 +117,7 @@
             goto out_free;
         }
 
-        if (ec_master_init(master, i, ec_eoe_devices))
+        if (ec_master_init(master, i, ec_eoeif_count))
             goto out_free;
 
         if (kobject_add(&master->kobj)) {
@@ -237,33 +237,38 @@
    Prints slave states in clear text.
 */
 
-void ec_print_states(const uint8_t states /**< slave states */)
-{
+size_t ec_state_string(uint8_t states, /**< slave states */
+                       char *buffer /**< target buffer (min. 25 bytes) */
+                       )
+{
+    off_t off = 0;
     unsigned int first = 1;
 
     if (!states) {
-        printk("(unknown)");
-        return;
+        off += sprintf(buffer + off, "(unknown)");
+        return off;
     }
 
     if (states & EC_SLAVE_STATE_INIT) {
-        printk("INIT");
+        off += sprintf(buffer + off, "INIT");
         first = 0;
     }
     if (states & EC_SLAVE_STATE_PREOP) {
-        if (!first) printk(", ");
-        printk("PREOP");
+        if (!first) off += sprintf(buffer + off, ", ");
+        off += sprintf(buffer + off, "PREOP");
         first = 0;
     }
     if (states & EC_SLAVE_STATE_SAVEOP) {
-        if (!first) printk(", ");
-        printk("SAVEOP");
+        if (!first) off += sprintf(buffer + off, ", ");
+        off += sprintf(buffer + off, "SAVEOP");
         first = 0;
     }
     if (states & EC_SLAVE_STATE_OP) {
-        if (!first) printk(", ");
-        printk("OP");
-    }
+        if (!first) off += sprintf(buffer + off, ", ");
+        off += sprintf(buffer + off, "OP");
+    }
+
+    return off;
 }
 
 /******************************************************************************
@@ -350,7 +355,7 @@
    Starts the master associated with the device.
    This function has to be called by the network device driver to tell the
    master that the device is ready to send and receive data. The master
-   will enter the free-run mode then.
+   will enter the idle mode then.
    \ingroup DeviceInterface
 */
 
@@ -364,7 +369,7 @@
         return -1;
     }
 
-    ec_master_freerun_start(master);
+    ec_master_idle_start(master);
     return 0;
 }
 
@@ -382,7 +387,7 @@
     ec_master_t *master;
     if (!(master = ec_find_master(master_index))) return;
 
-    ec_master_freerun_stop(master);
+    ec_master_idle_stop(master);
 
     if (ec_device_close(master->device))
         EC_WARN("Failed to close device!\n");
@@ -424,9 +429,9 @@
         goto out_release;
     }
 
-    ec_master_freerun_stop(master);
+    ec_master_idle_stop(master);
     ec_master_reset(master);
-    master->mode = EC_MASTER_MODE_RUNNING;
+    master->mode = EC_MASTER_MODE_OPERATION;
 
     if (!master->device->link_state) EC_WARN("Link is DOWN.\n");
 
@@ -441,7 +446,7 @@
  out_module_put:
     module_put(master->device->module);
     ec_master_reset(master);
-    ec_master_freerun_start(master);
+    ec_master_idle_start(master);
  out_release:
     master->reserved = 0;
  out_return:
@@ -466,9 +471,7 @@
     }
 
     ec_master_reset(master);
-
-    master->mode = EC_MASTER_MODE_IDLE;
-    ec_master_freerun_start(master);
+    ec_master_idle_start(master);
 
     module_put(master->device->module);
     master->reserved = 0;
--- a/master/slave.c	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/slave.c	Thu Aug 03 12:59:01 2006 +0000
@@ -52,7 +52,6 @@
 
 /*****************************************************************************/
 
-int ec_slave_fetch_categories(ec_slave_t *);
 ssize_t ec_show_slave_attribute(struct kobject *, struct attribute *, char *);
 ssize_t ec_store_slave_attribute(struct kobject *, struct attribute *,
                                  const char *, size_t);
@@ -61,24 +60,12 @@
 
 /** \cond */
 
-EC_SYSFS_READ_ATTR(ring_position);
-EC_SYSFS_READ_ATTR(coupler_address);
-EC_SYSFS_READ_ATTR(vendor_name);
-EC_SYSFS_READ_ATTR(product_name);
-EC_SYSFS_READ_ATTR(product_desc);
-EC_SYSFS_READ_ATTR(sii_name);
-EC_SYSFS_READ_ATTR(type);
+EC_SYSFS_READ_ATTR(info);
 EC_SYSFS_READ_WRITE_ATTR(state);
 EC_SYSFS_READ_WRITE_ATTR(eeprom);
 
 static struct attribute *def_attrs[] = {
-    &attr_ring_position,
-    &attr_coupler_address,
-    &attr_vendor_name,
-    &attr_product_name,
-    &attr_product_desc,
-    &attr_sii_name,
-    &attr_type,
+    &attr_info,
     &attr_state,
     &attr_eeprom,
     NULL,
@@ -127,13 +114,28 @@
     }
 
     slave->master = master;
+
+    slave->requested_state = EC_SLAVE_STATE_UNKNOWN;
+    slave->current_state = EC_SLAVE_STATE_UNKNOWN;
+    slave->error_flag = 0;
+    slave->online = 1;
+    slave->fmmu_count = 0;
+    slave->registered = 0;
+
     slave->coupler_index = 0;
     slave->coupler_subindex = 0xFFFF;
+
     slave->base_type = 0;
     slave->base_revision = 0;
     slave->base_build = 0;
     slave->base_fmmu_count = 0;
     slave->base_sync_count = 0;
+
+    slave->eeprom_data = NULL;
+    slave->eeprom_size = 0;
+    slave->new_eeprom_data = NULL;
+    slave->new_eeprom_size = 0;
+
     slave->sii_alias = 0;
     slave->sii_vendor_id = 0;
     slave->sii_product_code = 0;
@@ -144,25 +146,14 @@
     slave->sii_tx_mailbox_offset = 0;
     slave->sii_tx_mailbox_size = 0;
     slave->sii_mailbox_protocols = 0;
-    slave->type = NULL;
-    slave->registered = 0;
-    slave->fmmu_count = 0;
-    slave->eeprom_data = NULL;
-    slave->eeprom_size = 0;
-    slave->eeprom_group = NULL;
-    slave->eeprom_image = NULL;
-    slave->eeprom_order = NULL;
-    slave->eeprom_name = NULL;
-    slave->requested_state = EC_SLAVE_STATE_UNKNOWN;
-    slave->current_state = EC_SLAVE_STATE_UNKNOWN;
-    slave->error_flag = 0;
-    slave->online = 1;
-    slave->new_eeprom_data = NULL;
-    slave->new_eeprom_size = 0;
-
-    INIT_LIST_HEAD(&slave->eeprom_strings);
-    INIT_LIST_HEAD(&slave->eeprom_syncs);
-    INIT_LIST_HEAD(&slave->eeprom_pdos);
+    slave->sii_group = NULL;
+    slave->sii_image = NULL;
+    slave->sii_order = NULL;
+    slave->sii_name = NULL;
+
+    INIT_LIST_HEAD(&slave->sii_strings);
+    INIT_LIST_HEAD(&slave->sii_syncs);
+    INIT_LIST_HEAD(&slave->sii_pdos);
     INIT_LIST_HEAD(&slave->sdo_dictionary);
     INIT_LIST_HEAD(&slave->varsize_fields);
 
@@ -185,10 +176,10 @@
 void ec_slave_clear(struct kobject *kobj /**< kobject of the slave */)
 {
     ec_slave_t *slave;
-    ec_eeprom_string_t *string, *next_str;
-    ec_eeprom_sync_t *sync, *next_sync;
-    ec_eeprom_pdo_t *pdo, *next_pdo;
-    ec_eeprom_pdo_entry_t *entry, *next_ent;
+    ec_sii_string_t *string, *next_str;
+    ec_sii_sync_t *sync, *next_sync;
+    ec_sii_pdo_t *pdo, *next_pdo;
+    ec_sii_pdo_entry_t *entry, *next_ent;
     ec_sdo_t *sdo, *next_sdo;
     ec_sdo_entry_t *en, *next_en;
     ec_varsize_t *var, *next_var;
@@ -196,19 +187,19 @@
     slave = container_of(kobj, ec_slave_t, kobj);
 
     // free all string objects
-    list_for_each_entry_safe(string, next_str, &slave->eeprom_strings, list) {
+    list_for_each_entry_safe(string, next_str, &slave->sii_strings, list) {
         list_del(&string->list);
         kfree(string);
     }
 
     // free all sync managers
-    list_for_each_entry_safe(sync, next_sync, &slave->eeprom_syncs, list) {
+    list_for_each_entry_safe(sync, next_sync, &slave->sii_syncs, list) {
         list_del(&sync->list);
         kfree(sync);
     }
 
     // free all PDOs
-    list_for_each_entry_safe(pdo, next_pdo, &slave->eeprom_pdos, list) {
+    list_for_each_entry_safe(pdo, next_pdo, &slave->sii_pdos, list) {
         list_del(&pdo->list);
         if (pdo->name) kfree(pdo->name);
 
@@ -222,10 +213,10 @@
         kfree(pdo);
     }
 
-    if (slave->eeprom_group) kfree(slave->eeprom_group);
-    if (slave->eeprom_image) kfree(slave->eeprom_image);
-    if (slave->eeprom_order) kfree(slave->eeprom_order);
-    if (slave->eeprom_name) kfree(slave->eeprom_name);
+    if (slave->sii_group) kfree(slave->sii_group);
+    if (slave->sii_image) kfree(slave->sii_image);
+    if (slave->sii_order) kfree(slave->sii_order);
+    if (slave->sii_name) kfree(slave->sii_name);
 
     // free all SDOs
     list_for_each_entry_safe(sdo, next_sdo, &slave->sdo_dictionary, list) {
@@ -253,371 +244,6 @@
 /*****************************************************************************/
 
 /**
-   Reads all necessary information from a slave.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_fetch(ec_slave_t *slave /**< EtherCAT slave */)
-{
-    ec_datagram_t *datagram;
-    unsigned int i;
-    uint16_t dl_status;
-
-    datagram = &slave->master->simple_datagram;
-
-    // read base data
-    if (ec_datagram_nprd(datagram, slave->station_address, 0x0000, 6))
-        return -1;
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("Reading base data from slave %i failed!\n",
-               slave->ring_position);
-        return -1;
-    }
-
-    slave->base_type =       EC_READ_U8 (datagram->data);
-    slave->base_revision =   EC_READ_U8 (datagram->data + 1);
-    slave->base_build =      EC_READ_U16(datagram->data + 2);
-    slave->base_fmmu_count = EC_READ_U8 (datagram->data + 4);
-    slave->base_sync_count = EC_READ_U8 (datagram->data + 5);
-
-    if (slave->base_fmmu_count > EC_MAX_FMMUS)
-        slave->base_fmmu_count = EC_MAX_FMMUS;
-
-    // read data link status
-    if (ec_datagram_nprd(datagram, slave->station_address, 0x0110, 2))
-        return -1;
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("Reading DL status from slave %i failed!\n",
-               slave->ring_position);
-        return -1;
-    }
-
-    dl_status = EC_READ_U16(datagram->data);
-    for (i = 0; i < 4; i++) {
-        slave->dl_link[i] = dl_status & (1 << (4 + i)) ? 1 : 0;
-        slave->dl_loop[i] = dl_status & (1 << (8 + i * 2)) ? 1 : 0;
-        slave->dl_signal[i] = dl_status & (1 << (9 + i * 2)) ? 1 : 0;
-    }
-
-    // read EEPROM data
-    if (ec_slave_sii_read16(slave, 0x0004, &slave->sii_alias))
-        return -1;
-    if (ec_slave_sii_read32(slave, 0x0008, &slave->sii_vendor_id))
-        return -1;
-    if (ec_slave_sii_read32(slave, 0x000A, &slave->sii_product_code))
-        return -1;
-    if (ec_slave_sii_read32(slave, 0x000C, &slave->sii_revision_number))
-        return -1;
-    if (ec_slave_sii_read32(slave, 0x000E, &slave->sii_serial_number))
-        return -1;
-    if (ec_slave_sii_read16(slave, 0x0018, &slave->sii_rx_mailbox_offset))
-        return -1;
-    if (ec_slave_sii_read16(slave, 0x0019, &slave->sii_rx_mailbox_size))
-        return -1;
-    if (ec_slave_sii_read16(slave, 0x001A, &slave->sii_tx_mailbox_offset))
-        return -1;
-    if (ec_slave_sii_read16(slave, 0x001B, &slave->sii_tx_mailbox_size))
-        return -1;
-    if (ec_slave_sii_read16(slave, 0x001C, &slave->sii_mailbox_protocols))
-        return -1;
-
-    if (unlikely(ec_slave_fetch_categories(slave))) {
-        EC_ERR("Failed to fetch category data!\n");
-        return -1;
-    }
-
-    return 0;
-}
-
-/*****************************************************************************/
-
-/**
-   Reads 16 bit from the slave information interface (SII).
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_sii_read16(ec_slave_t *slave,
-                        /**< EtherCAT slave */
-                        uint16_t offset,
-                        /**< address of the SII register to read */
-                        uint16_t *target
-                        /**< target memory */
-                        )
-{
-    ec_datagram_t *datagram;
-    cycles_t start, end, timeout;
-
-    datagram = &slave->master->simple_datagram;
-
-    // initiate read operation
-    if (ec_datagram_npwr(datagram, slave->station_address, 0x502, 6))
-        return -1;
-    EC_WRITE_U8 (datagram->data,     0x00); // read-only access
-    EC_WRITE_U8 (datagram->data + 1, 0x01); // request read operation
-    EC_WRITE_U32(datagram->data + 2, offset);
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("SII-read failed on slave %i!\n", slave->ring_position);
-        return -1;
-    }
-
-    start = get_cycles();
-    timeout = (cycles_t) 100 * cpu_khz; // 100ms
-
-    while (1)
-    {
-        udelay(10);
-
-        if (ec_datagram_nprd(datagram, slave->station_address, 0x502, 10))
-            return -1;
-        if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-            EC_ERR("Getting SII-read status failed on slave %i!\n",
-                   slave->ring_position);
-            return -1;
-        }
-
-        end = get_cycles();
-
-        // check for "busy bit"
-        if (likely((EC_READ_U8(datagram->data + 1) & 0x81) == 0)) {
-            *target = EC_READ_U16(datagram->data + 6);
-            return 0;
-        }
-
-        if (unlikely((end - start) >= timeout)) {
-            EC_ERR("SII-read. Slave %i timed out!\n", slave->ring_position);
-            return -1;
-        }
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   Reads 32 bit from the slave information interface (SII).
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_sii_read32(ec_slave_t *slave,
-                        /**< EtherCAT slave */
-                        uint16_t offset,
-                        /**< address of the SII register to read */
-                        uint32_t *target
-                        /**< target memory */
-                        )
-{
-    ec_datagram_t *datagram;
-    cycles_t start, end, timeout;
-
-    datagram = &slave->master->simple_datagram;
-
-    // initiate read operation
-    if (ec_datagram_npwr(datagram, slave->station_address, 0x502, 6))
-        return -1;
-    EC_WRITE_U8 (datagram->data,     0x00); // read-only access
-    EC_WRITE_U8 (datagram->data + 1, 0x01); // request read operation
-    EC_WRITE_U32(datagram->data + 2, offset);
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("SII-read failed on slave %i!\n", slave->ring_position);
-        return -1;
-    }
-
-    start = get_cycles();
-    timeout = (cycles_t) 100 * cpu_khz; // 100ms
-
-    while (1)
-    {
-        udelay(10);
-
-        if (ec_datagram_nprd(datagram, slave->station_address, 0x502, 10))
-            return -1;
-        if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-            EC_ERR("Getting SII-read status failed on slave %i!\n",
-                   slave->ring_position);
-            return -1;
-        }
-
-        end = get_cycles();
-
-        // check "busy bit"
-        if (likely((EC_READ_U8(datagram->data + 1) & 0x81) == 0)) {
-            *target = EC_READ_U32(datagram->data + 6);
-            return 0;
-        }
-
-        if (unlikely((end - start) >= timeout)) {
-            EC_ERR("SII-read. Slave %i timed out!\n", slave->ring_position);
-            return -1;
-        }
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   Writes 16 bit of data to the slave information interface (SII).
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_sii_write16(ec_slave_t *slave,
-                         /**< EtherCAT slave */
-                         uint16_t offset,
-                         /**< address of the SII register to write */
-                         uint16_t value
-                         /**< new value */
-                         )
-{
-    ec_datagram_t *datagram;
-    cycles_t start, end, timeout;
-
-    datagram = &slave->master->simple_datagram;
-
-    EC_INFO("SII-write (slave %i, offset 0x%04X, value 0x%04X)\n",
-            slave->ring_position, offset, value);
-
-    // initiate write operation
-    if (ec_datagram_npwr(datagram, slave->station_address, 0x502, 8))
-        return -1;
-    EC_WRITE_U8 (datagram->data,     0x01); // enable write access
-    EC_WRITE_U8 (datagram->data + 1, 0x02); // request write operation
-    EC_WRITE_U32(datagram->data + 2, offset);
-    EC_WRITE_U16(datagram->data + 6, value);
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("SII-write failed on slave %i!\n", slave->ring_position);
-        return -1;
-    }
-
-    start = get_cycles();
-    timeout = (cycles_t) 100 * cpu_khz; // 100ms
-
-    while (1)
-    {
-        udelay(10);
-
-        if (ec_datagram_nprd(datagram, slave->station_address, 0x502, 2))
-            return -1;
-        if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-            EC_ERR("Getting SII-write status failed on slave %i!\n",
-                   slave->ring_position);
-            return -1;
-        }
-
-        end = get_cycles();
-
-        // check "busy bit"
-        if (likely((EC_READ_U8(datagram->data + 1) & 0x82) == 0)) {
-            if (EC_READ_U8(datagram->data + 1) & 0x40) {
-                EC_ERR("SII-write failed!\n");
-                return -1;
-            }
-            else {
-                EC_INFO("SII-write succeeded!\n");
-                return 0;
-            }
-        }
-
-        if (unlikely((end - start) >= timeout)) {
-            EC_ERR("SII-write: Slave %i timed out!\n", slave->ring_position);
-            return -1;
-        }
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   Fetches data from slave's EEPROM.
-   \return 0 in case of success, else < 0
-   \todo memory allocation
-*/
-
-int ec_slave_fetch_categories(ec_slave_t *slave /**< EtherCAT slave */)
-{
-    uint16_t word_offset, cat_type, word_count;
-    uint32_t value;
-    uint8_t *cat_data;
-    unsigned int i;
-
-    word_offset = 0x0040;
-
-    if (!(cat_data = (uint8_t *) kmalloc(0x10000, GFP_ATOMIC))) {
-        EC_ERR("Failed to allocate 64k bytes for category data.\n");
-        return -1;
-    }
-
-    while (1) {
-        // read category type
-        if (ec_slave_sii_read32(slave, word_offset, &value)) {
-            EC_ERR("Unable to read category header.\n");
-            goto out_free;
-        }
-
-        // last category?
-        if ((value & 0xFFFF) == 0xFFFF) break;
-
-        cat_type = value & 0x7FFF;
-        word_count = (value >> 16) & 0xFFFF;
-
-        // fetch category data
-        for (i = 0; i < word_count; i++) {
-            if (ec_slave_sii_read32(slave, word_offset + 2 + i, &value)) {
-                EC_ERR("Unable to read category data word %i.\n", i);
-                goto out_free;
-            }
-
-            cat_data[i * 2]     = (value >> 0) & 0xFF;
-            cat_data[i * 2 + 1] = (value >> 8) & 0xFF;
-
-            // read second word "on the fly"
-            if (i + 1 < word_count) {
-                i++;
-                cat_data[i * 2]     = (value >> 16) & 0xFF;
-                cat_data[i * 2 + 1] = (value >> 24) & 0xFF;
-            }
-        }
-
-        switch (cat_type)
-        {
-            case 0x000A:
-                if (ec_slave_fetch_strings(slave, cat_data))
-                    goto out_free;
-                break;
-            case 0x001E:
-                if (ec_slave_fetch_general(slave, cat_data))
-                    goto out_free;
-                break;
-            case 0x0028:
-                break;
-            case 0x0029:
-                if (ec_slave_fetch_sync(slave, cat_data, word_count))
-                    goto out_free;
-                break;
-            case 0x0032:
-                if (ec_slave_fetch_pdo(slave, cat_data, word_count, EC_TX_PDO))
-                    goto out_free;
-                break;
-            case 0x0033:
-                if (ec_slave_fetch_pdo(slave, cat_data, word_count, EC_RX_PDO))
-                    goto out_free;
-                break;
-            default:
-                EC_WARN("Unknown category type 0x%04X in slave %i.\n",
-                        cat_type, slave->ring_position);
-        }
-
-        word_offset += 2 + word_count;
-    }
-
-    kfree(cat_data);
-    return 0;
-
- out_free:
-    kfree(cat_data);
-    return -1;
-}
-
-/*****************************************************************************/
-
-/**
    Fetches data from a STRING category.
    \return 0 in case of success, else < 0
 */
@@ -629,24 +255,24 @@
     unsigned int string_count, i;
     size_t size;
     off_t offset;
-    ec_eeprom_string_t *string;
+    ec_sii_string_t *string;
 
     string_count = data[0];
     offset = 1;
     for (i = 0; i < string_count; i++) {
         size = data[offset];
         // allocate memory for string structure and data at a single blow
-        if (!(string = (ec_eeprom_string_t *)
-              kmalloc(sizeof(ec_eeprom_string_t) + size + 1, GFP_ATOMIC))) {
+        if (!(string = (ec_sii_string_t *)
+              kmalloc(sizeof(ec_sii_string_t) + size + 1, GFP_ATOMIC))) {
             EC_ERR("Failed to allocate string memory.\n");
             return -1;
         }
         string->size = size;
         // string memory appended to string structure
-        string->data = (char *) string + sizeof(ec_eeprom_string_t);
+        string->data = (char *) string + sizeof(ec_sii_string_t);
         memcpy(string->data, data + offset + 1, size);
         string->data[size] = 0x00;
-        list_add_tail(&string->list, &slave->eeprom_strings);
+        list_add_tail(&string->list, &slave->sii_strings);
         offset += 1 + size;
     }
 
@@ -660,26 +286,20 @@
    \return 0 in case of success, else < 0
 */
 
-int ec_slave_fetch_general(ec_slave_t *slave, /**< EtherCAT slave */
-                           const uint8_t *data /**< category data */
-                           )
+void ec_slave_fetch_general(ec_slave_t *slave, /**< EtherCAT slave */
+                            const uint8_t *data /**< category data */
+                            )
 {
     unsigned int i;
 
-    if (ec_slave_locate_string(slave, data[0], &slave->eeprom_group))
-        return -1;
-    if (ec_slave_locate_string(slave, data[1], &slave->eeprom_image))
-        return -1;
-    if (ec_slave_locate_string(slave, data[2], &slave->eeprom_order))
-        return -1;
-    if (ec_slave_locate_string(slave, data[3], &slave->eeprom_name))
-        return -1;
+    ec_slave_locate_string(slave, data[0], &slave->sii_group);
+    ec_slave_locate_string(slave, data[1], &slave->sii_image);
+    ec_slave_locate_string(slave, data[2], &slave->sii_order);
+    ec_slave_locate_string(slave, data[3], &slave->sii_name);
 
     for (i = 0; i < 4; i++)
         slave->sii_physical_layer[i] =
             (data[4] & (0x03 << (i * 2))) >> (i * 2);
-
-    return 0;
 }
 
 /*****************************************************************************/
@@ -695,24 +315,24 @@
                         )
 {
     unsigned int sync_count, i;
-    ec_eeprom_sync_t *sync;
+    ec_sii_sync_t *sync;
 
     sync_count = word_count / 4; // sync manager struct is 4 words long
 
     for (i = 0; i < sync_count; i++, data += 8) {
-        if (!(sync = (ec_eeprom_sync_t *)
-              kmalloc(sizeof(ec_eeprom_sync_t), GFP_ATOMIC))) {
+        if (!(sync = (ec_sii_sync_t *)
+              kmalloc(sizeof(ec_sii_sync_t), GFP_ATOMIC))) {
             EC_ERR("Failed to allocate Sync-Manager memory.\n");
             return -1;
         }
 
         sync->index = i;
-        sync->physical_start_address = *((uint16_t *) (data + 0));
-        sync->length                 = *((uint16_t *) (data + 2));
-        sync->control_register       = data[4];
-        sync->enable                 = data[6];
-
-        list_add_tail(&sync->list, &slave->eeprom_syncs);
+        sync->physical_start_address = EC_READ_U16(data);
+        sync->length                 = EC_READ_U16(data + 2);
+        sync->control_register       = EC_READ_U8 (data + 4);
+        sync->enable                 = EC_READ_U8 (data + 6);
+
+        list_add_tail(&sync->list, &slave->sii_syncs);
     }
 
     return 0;
@@ -728,16 +348,16 @@
 int ec_slave_fetch_pdo(ec_slave_t *slave, /**< EtherCAT slave */
                        const uint8_t *data, /**< category data */
                        size_t word_count, /**< number of words */
-                       ec_pdo_type_t pdo_type /**< PDO type */
+                       ec_sii_pdo_type_t pdo_type /**< PDO type */
                        )
 {
-    ec_eeprom_pdo_t *pdo;
-    ec_eeprom_pdo_entry_t *entry;
+    ec_sii_pdo_t *pdo;
+    ec_sii_pdo_entry_t *entry;
     unsigned int entry_count, i;
 
     while (word_count >= 4) {
-        if (!(pdo = (ec_eeprom_pdo_t *)
-              kmalloc(sizeof(ec_eeprom_pdo_t), GFP_ATOMIC))) {
+        if (!(pdo = (ec_sii_pdo_t *)
+              kmalloc(sizeof(ec_sii_pdo_t), GFP_ATOMIC))) {
             EC_ERR("Failed to allocate PDO memory.\n");
             return -1;
         }
@@ -745,29 +365,29 @@
         INIT_LIST_HEAD(&pdo->entries);
         pdo->type = pdo_type;
 
-        pdo->index = *((uint16_t *) data);
-        entry_count = data[2];
-        pdo->sync_manager = data[3];
+        pdo->index = EC_READ_U16(data);
+        entry_count = EC_READ_U8(data + 2);
+        pdo->sync_index = EC_READ_U8(data + 3);
         pdo->name = NULL;
-        ec_slave_locate_string(slave, data[5], &pdo->name);
-
-        list_add_tail(&pdo->list, &slave->eeprom_pdos);
+        ec_slave_locate_string(slave, EC_READ_U8(data + 5), &pdo->name);
+
+        list_add_tail(&pdo->list, &slave->sii_pdos);
 
         word_count -= 4;
         data += 8;
 
         for (i = 0; i < entry_count; i++) {
-            if (!(entry = (ec_eeprom_pdo_entry_t *)
-                  kmalloc(sizeof(ec_eeprom_pdo_entry_t), GFP_ATOMIC))) {
+            if (!(entry = (ec_sii_pdo_entry_t *)
+                  kmalloc(sizeof(ec_sii_pdo_entry_t), GFP_ATOMIC))) {
                 EC_ERR("Failed to allocate PDO entry memory.\n");
                 return -1;
             }
 
-            entry->index = *((uint16_t *) data);
-            entry->subindex = data[2];
+            entry->index = EC_READ_U16(data);
+            entry->subindex = EC_READ_U8(data + 2);
             entry->name = NULL;
-            ec_slave_locate_string(slave, data[3], &entry->name);
-            entry->bit_length = data[5];
+            ec_slave_locate_string(slave, EC_READ_U8(data + 3), &entry->name);
+            entry->bit_length = EC_READ_U8(data + 5);
 
             list_add_tail(&entry->list, &pdo->entries);
 
@@ -792,7 +412,7 @@
                            char **ptr /**< Address of the string pointer */
                            )
 {
-    ec_eeprom_string_t *string;
+    ec_sii_string_t *string;
     char *err_string;
 
     // Erst alten Speicher freigeben
@@ -805,7 +425,7 @@
     if (!index) return 0;
 
     // EEPROM-String mit Index finden und kopieren
-    list_for_each_entry(string, &slave->eeprom_strings, list) {
+    list_for_each_entry(string, &slave->sii_strings, list) {
         if (--index) continue;
 
         if (!(*ptr = (char *) kmalloc(string->size + 1, GFP_ATOMIC))) {
@@ -821,7 +441,7 @@
     err_string = "(string not found)";
 
     if (!(*ptr = (char *) kmalloc(strlen(err_string) + 1, GFP_ATOMIC))) {
-        EC_ERR("Unable to allocate string memory.\n");
+        EC_WARN("Unable to allocate string memory.\n");
         return -1;
     }
 
@@ -832,175 +452,11 @@
 /*****************************************************************************/
 
 /**
-   Acknowledges an error after a state transition.
-*/
-
-void ec_slave_state_ack(ec_slave_t *slave, /**< EtherCAT slave */
-                        uint8_t state /**< previous state */
-                        )
-{
-    ec_datagram_t *datagram;
-    cycles_t start, end, timeout;
-
-    datagram = &slave->master->simple_datagram;
-
-    if (ec_datagram_npwr(datagram, slave->station_address, 0x0120, 2)) return;
-    EC_WRITE_U16(datagram->data, state | EC_ACK);
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_WARN("Acknowledge sending failed on slave %i!\n",
-                slave->ring_position);
-        return;
-    }
-
-    start = get_cycles();
-    timeout = (cycles_t) 10 * cpu_khz; // 10ms
-
-    while (1)
-    {
-        udelay(100); // wait a little bit...
-
-        if (ec_datagram_nprd(datagram, slave->station_address, 0x0130, 2))
-            return;
-        if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-            slave->current_state = EC_SLAVE_STATE_UNKNOWN;
-            EC_WARN("Acknowledge checking failed on slave %i!\n",
-                    slave->ring_position);
-            return;
-        }
-
-        end = get_cycles();
-
-        if (likely(EC_READ_U8(datagram->data) == state)) {
-            slave->current_state = state;
-            EC_INFO("Acknowleged state 0x%02X on slave %i.\n", state,
-                    slave->ring_position);
-            return;
-        }
-
-        if (unlikely((end - start) >= timeout)) {
-            slave->current_state = EC_SLAVE_STATE_UNKNOWN;
-            EC_WARN("Failed to acknowledge state 0x%02X on slave %i"
-                    " - Timeout!\n", state, slave->ring_position);
-            return;
-        }
-    }
-}
-
-/*****************************************************************************/
-
-/**
-   Reads the AL status code of a slave and displays it.
-   If the AL status code is not supported, or if no error occurred (both
-   resulting in code = 0), nothing is displayed.
-*/
-
-void ec_slave_read_al_status_code(ec_slave_t *slave /**< EtherCAT slave */)
-{
-    ec_datagram_t *datagram;
-    uint16_t code;
-    const ec_code_msg_t *al_msg;
-
-    datagram = &slave->master->simple_datagram;
-
-    if (ec_datagram_nprd(datagram, slave->station_address, 0x0134, 2)) return;
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_WARN("Failed to read AL status code on slave %i!\n",
-                slave->ring_position);
-        return;
-    }
-
-    if (!(code = EC_READ_U16(datagram->data))) return;
-
-    for (al_msg = al_status_messages; al_msg->code; al_msg++) {
-        if (al_msg->code == code) {
-            EC_ERR("AL status message 0x%04X: \"%s\".\n",
-                   al_msg->code, al_msg->message);
-            return;
-        }
-    }
-
-    EC_ERR("Unknown AL status code 0x%04X.\n", code);
-}
-
-/*****************************************************************************/
-
-/**
-   Does a state transition.
-   \return 0 in case of success, else < 0
-*/
-
-int ec_slave_state_change(ec_slave_t *slave, /**< EtherCAT slave */
-                          uint8_t state /**< new state */
-                          )
-{
-    ec_datagram_t *datagram;
-    cycles_t start, end, timeout;
-
-    datagram = &slave->master->simple_datagram;
-
-    slave->requested_state = state;
-
-    if (ec_datagram_npwr(datagram, slave->station_address, 0x0120, 2))
-        return -1;
-    EC_WRITE_U16(datagram->data, state);
-    if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-        EC_ERR("Failed to set state 0x%02X on slave %i!\n",
-               state, slave->ring_position);
-        return -1;
-    }
-
-    start = get_cycles();
-    timeout = (cycles_t) 10 * cpu_khz; // 10ms
-
-    while (1)
-    {
-        udelay(100); // wait a little bit
-
-        if (ec_datagram_nprd(datagram, slave->station_address, 0x0130, 2))
-            return -1;
-        if (unlikely(ec_master_simple_io(slave->master, datagram))) {
-            slave->current_state = EC_SLAVE_STATE_UNKNOWN;
-            EC_ERR("Failed to check state 0x%02X on slave %i!\n",
-                   state, slave->ring_position);
-            return -1;
-        }
-
-        end = get_cycles();
-
-        if (unlikely(EC_READ_U8(datagram->data) & 0x10)) {
-            // state change error
-            EC_ERR("Failed to set state 0x%02X - Slave %i refused state change"
-                   " (code 0x%02X)!\n", state, slave->ring_position,
-                   EC_READ_U8(datagram->data));
-            slave->current_state = EC_READ_U8(datagram->data);
-            state = slave->current_state & 0x0F;
-            ec_slave_read_al_status_code(slave);
-            ec_slave_state_ack(slave, state);
-            return -1;
-        }
-
-        if (likely(EC_READ_U8(datagram->data) == (state & 0x0F))) {
-            slave->current_state = state;
-            return 0; // state change successful
-        }
-
-        if (unlikely((end - start) >= timeout)) {
-            slave->current_state = EC_SLAVE_STATE_UNKNOWN;
-            EC_ERR("Failed to check state 0x%02X of slave %i - Timeout!\n",
-                   state, slave->ring_position);
-            return -1;
-        }
-    }
-}
-
-/*****************************************************************************/
-
-/**
    Prepares an FMMU configuration.
    Configuration data for the FMMU is saved in the slave structure and is
    written to the slave in ecrt_master_activate().
    The FMMU configuration is done in a way, that the complete data range
-   of the corresponding sync manager is covered. Seperate FMMUs arce configured
+   of the corresponding sync manager is covered. Seperate FMMUs are configured
    for each domain.
    If the FMMU configuration is already prepared, the function returns with
    success.
@@ -1009,7 +465,7 @@
 
 int ec_slave_prepare_fmmu(ec_slave_t *slave, /**< EtherCAT slave */
                           const ec_domain_t *domain, /**< domain */
-                          const ec_sync_t *sync  /**< sync manager */
+                          const ec_sii_sync_t *sync  /**< sync manager */
                           )
 {
     unsigned int i;
@@ -1039,171 +495,152 @@
 
 /**
    Outputs all information about a certain slave.
-   Verbosity:
-   - 0: Only slave types and addresses
-   - 1: with EEPROM information
-   - >1: with SDO dictionaries
-*/
-
-void ec_slave_print(const ec_slave_t *slave, /**< EtherCAT slave */
-                    unsigned int verbosity /**< verbosity level */
-                    )
-{
-    ec_eeprom_sync_t *sync;
-    ec_eeprom_pdo_t *pdo;
-    ec_eeprom_pdo_entry_t *pdo_entry;
-    ec_sdo_t *sdo;
-    ec_sdo_entry_t *sdo_entry;
+*/
+
+size_t ec_slave_info(const ec_slave_t *slave, /**< EtherCAT slave */
+                     char *buffer /**< Output buffer */
+                     )
+{
+    off_t off = 0;
+    ec_sii_sync_t *sync;
+    ec_sii_pdo_t *pdo;
+    ec_sii_pdo_entry_t *pdo_entry;
     int first, i;
 
-    if (slave->type) {
-        EC_INFO("%i) %s %s: %s\n", slave->ring_position,
-                slave->type->vendor_name, slave->type->product_name,
-                slave->type->description);
-    }
-    else {
-        EC_INFO("%i) UNKNOWN SLAVE: vendor 0x%08X, product 0x%08X\n",
-                slave->ring_position, slave->sii_vendor_id,
-                slave->sii_product_code);
-    }
-
-    if (!verbosity) return;
-
-    EC_INFO("  Station address: 0x%04X\n", slave->station_address);
-
-    EC_INFO("  Data link status:\n");
+    off += sprintf(buffer + off, "\nName: ");
+
+    if (slave->sii_name)
+        off += sprintf(buffer + off, "%s", slave->sii_name);
+
+    off += sprintf(buffer + off, "\n\nVendor ID: 0x%08X\n",
+                   slave->sii_vendor_id);
+    off += sprintf(buffer + off, "Product code: 0x%08X\n\n",
+                   slave->sii_product_code);
+
+    off += sprintf(buffer + off, "Ring position: %i\n", slave->ring_position);
+    off += sprintf(buffer + off, "Advanced position: %i:%i\n\n",
+                   slave->coupler_index, slave->coupler_subindex);
+
+    off += sprintf(buffer + off, "State: ");
+    off += ec_state_string(slave->current_state, buffer + off);
+    off += sprintf(buffer + off, "\n\n");
+
+    off += sprintf(buffer + off, "Data link status:\n");
     for (i = 0; i < 4; i++) {
-        EC_INFO("    Port %i (", i);
+        off += sprintf(buffer + off, "  Port %i (", i);
         switch (slave->sii_physical_layer[i]) {
             case 0x00:
-                printk("EBUS");
+                off += sprintf(buffer + off, "EBUS");
                 break;
             case 0x01:
-                printk("100BASE-TX");
+                off += sprintf(buffer + off, "100BASE-TX");
                 break;
             case 0x02:
-                printk("100BASE-FX");
+                off += sprintf(buffer + off, "100BASE-FX");
                 break;
             default:
-                printk("unknown");
-        }
-        printk(")\n");
-        EC_INFO("      link %s, loop %s, %s\n",
-                slave->dl_link[i] ? "up" : "down",
-                slave->dl_loop[i] ? "closed" : "open",
-                slave->dl_signal[i] ? "signal detected" : "no signal");
-    }
-
-    EC_INFO("  Base information:\n");
-    EC_INFO("    Type %u, revision %i, build %i\n",
-            slave->base_type, slave->base_revision, slave->base_build);
-    EC_INFO("    Supported FMMUs: %i, sync managers: %i\n",
-            slave->base_fmmu_count, slave->base_sync_count);
+                off += sprintf(buffer + off, "unknown (%i)",
+                               slave->sii_physical_layer[i]);
+        }
+        off += sprintf(buffer + off, ") Link %s, Loop %s, %s\n",
+                       slave->dl_link[i] ? "up" : "down",
+                       slave->dl_loop[i] ? "closed" : "open",
+                       slave->dl_signal[i] ? "Signal detected" : "No signal");
+    }
 
     if (slave->sii_mailbox_protocols) {
-        EC_INFO("  Mailbox communication:\n");
-        EC_INFO("    RX mailbox: 0x%04X/%i, TX mailbox: 0x%04X/%i\n",
-                slave->sii_rx_mailbox_offset, slave->sii_rx_mailbox_size,
-                slave->sii_tx_mailbox_offset, slave->sii_tx_mailbox_size);
-        EC_INFO("    Supported protocols: ");
+        off += sprintf(buffer + off, "\nMailboxes:\n");
+        off += sprintf(buffer + off, "  RX mailbox: 0x%04X/%i,"
+                       " TX mailbox: 0x%04X/%i\n",
+                       slave->sii_rx_mailbox_offset,
+                       slave->sii_rx_mailbox_size,
+                       slave->sii_tx_mailbox_offset,
+                       slave->sii_tx_mailbox_size);
+        off += sprintf(buffer + off, "  Supported protocols: ");
 
         first = 1;
         if (slave->sii_mailbox_protocols & EC_MBOX_AOE) {
-            printk("AoE");
+            off += sprintf(buffer + off, "AoE");
             first = 0;
         }
         if (slave->sii_mailbox_protocols & EC_MBOX_EOE) {
-            if (!first) printk(", ");
-            printk("EoE");
+            if (!first) off += sprintf(buffer + off, ", ");
+            off += sprintf(buffer + off, "EoE");
             first = 0;
         }
         if (slave->sii_mailbox_protocols & EC_MBOX_COE) {
-            if (!first) printk(", ");
-            printk("CoE");
+            if (!first) off += sprintf(buffer + off, ", ");
+            off += sprintf(buffer + off, "CoE");
             first = 0;
         }
         if (slave->sii_mailbox_protocols & EC_MBOX_FOE) {
-            if (!first) printk(", ");
-            printk("FoE");
+            if (!first) off += sprintf(buffer + off, ", ");
+            off += sprintf(buffer + off, "FoE");
             first = 0;
         }
         if (slave->sii_mailbox_protocols & EC_MBOX_SOE) {
-            if (!first) printk(", ");
-            printk("SoE");
+            if (!first) off += sprintf(buffer + off, ", ");
+            off += sprintf(buffer + off, "SoE");
             first = 0;
         }
         if (slave->sii_mailbox_protocols & EC_MBOX_VOE) {
-            if (!first) printk(", ");
-            printk("VoE");
-        }
-        printk("\n");
-    }
-
-    EC_INFO("  EEPROM data:\n");
-
-    EC_INFO("    EEPROM content size: %i Bytes\n", slave->eeprom_size);
+            if (!first) off += sprintf(buffer + off, ", ");
+            off += sprintf(buffer + off, "VoE");
+        }
+        off += sprintf(buffer + off, "\n");
+    }
+
+    if (slave->sii_alias || slave->sii_group
+        || slave->sii_image || slave->sii_order)
+        off += sprintf(buffer + off, "\nSII data:\n");
 
     if (slave->sii_alias)
-        EC_INFO("    Configured station alias: 0x%04X (%i)\n",
-                slave->sii_alias, slave->sii_alias);
-
-    EC_INFO("    Vendor-ID: 0x%08X, Product code: 0x%08X\n",
-            slave->sii_vendor_id, slave->sii_product_code);
-    EC_INFO("    Revision number: 0x%08X, Serial number: 0x%08X\n",
-            slave->sii_revision_number, slave->sii_serial_number);
-
-    if (slave->eeprom_group)
-        EC_INFO("    Group: %s\n", slave->eeprom_group);
-    if (slave->eeprom_image)
-        EC_INFO("    Image: %s\n", slave->eeprom_image);
-    if (slave->eeprom_order)
-        EC_INFO("    Order#: %s\n", slave->eeprom_order);
-    if (slave->eeprom_name)
-        EC_INFO("    Name: %s\n", slave->eeprom_name);
-
-    if (!list_empty(&slave->eeprom_syncs)) {
-        EC_INFO("    Sync-Managers:\n");
-        list_for_each_entry(sync, &slave->eeprom_syncs, list) {
-            EC_INFO("      %i: 0x%04X, length %i, control 0x%02X, %s\n",
-                    sync->index, sync->physical_start_address,
-                    sync->length, sync->control_register,
-                    sync->enable ? "enable" : "disable");
-        }
-    }
-
-    list_for_each_entry(pdo, &slave->eeprom_pdos, list) {
-        EC_INFO("    %s \"%s\" (0x%04X), -> Sync-Manager %i\n",
-                pdo->type == EC_RX_PDO ? "RXPDO" : "TXPDO",
-                pdo->name ? pdo->name : "???",
-                pdo->index, pdo->sync_manager);
+        off += sprintf(buffer + off, "  Configured station alias:"
+                       " 0x%04X (%i)\n", slave->sii_alias, slave->sii_alias);
+    if (slave->sii_group)
+        off += sprintf(buffer + off, "  Group: %s\n", slave->sii_group);
+    if (slave->sii_image)
+        off += sprintf(buffer + off, "  Image: %s\n", slave->sii_image);
+    if (slave->sii_order)
+        off += sprintf(buffer + off, "  Order#: %s\n", slave->sii_order);
+
+    if (!list_empty(&slave->sii_syncs))
+        off += sprintf(buffer + off, "\nSync-Managers:\n");
+
+    list_for_each_entry(sync, &slave->sii_syncs, list) {
+        off += sprintf(buffer + off, "  %i: 0x%04X, length %i,"
+                       " control 0x%02X, %s\n",
+                       sync->index, sync->physical_start_address,
+                       sync->length, sync->control_register,
+                       sync->enable ? "enable" : "disable");
+    }
+
+    if (!list_empty(&slave->sii_pdos))
+        off += sprintf(buffer + off, "\nPDOs:\n");
+
+    list_for_each_entry(pdo, &slave->sii_pdos, list) {
+        off += sprintf(buffer + off,
+                       "  %s \"%s\" (0x%04X), -> Sync-Manager %i\n",
+                       pdo->type == EC_RX_PDO ? "RXPDO" : "TXPDO",
+                       pdo->name ? pdo->name : "???",
+                       pdo->index, pdo->sync_index);
 
         list_for_each_entry(pdo_entry, &pdo->entries, list) {
-            EC_INFO("      \"%s\" 0x%04X:%X, %i Bit\n",
-                    pdo_entry->name ? pdo_entry->name : "???",
-                    pdo_entry->index, pdo_entry->subindex,
-                    pdo_entry->bit_length);
-        }
-    }
-
-    if (verbosity < 2) return;
-
-    if (!list_empty(&slave->sdo_dictionary)) {
-        EC_INFO("    SDO-Dictionary:\n");
-        list_for_each_entry(sdo, &slave->sdo_dictionary, list) {
-            EC_INFO("      0x%04X \"%s\"\n", sdo->index,
-                    sdo->name ? sdo->name : "");
-            EC_INFO("        Object code: 0x%02X\n", sdo->object_code);
-            list_for_each_entry(sdo_entry, &sdo->entries, list) {
-                EC_INFO("        0x%04X:%i \"%s\", type 0x%04X, %i bits\n",
-                        sdo->index, sdo_entry->subindex,
-                        sdo_entry->name ? sdo_entry->name : "",
-                        sdo_entry->data_type, sdo_entry->bit_length);
-            }
-        }
-    }
-}
-
-/*****************************************************************************/
+            off += sprintf(buffer + off, "    \"%s\" 0x%04X:%X, %i Bit\n",
+                           pdo_entry->name ? pdo_entry->name : "???",
+                           pdo_entry->index, pdo_entry->subindex,
+                           pdo_entry->bit_length);
+        }
+    }
+
+    off += sprintf(buffer + off, "\n");
+
+    return off;
+}
+
+/*****************************************************************************/
+
+#if 0
 
 /**
    Outputs the values of the CRC faoult counters and resets them.
@@ -1260,6 +697,8 @@
     return 0;
 }
 
+#endif
+
 /*****************************************************************************/
 
 /**
@@ -1282,8 +721,8 @@
         return -1;
     }
 
-    if (slave->master->mode != EC_MASTER_MODE_FREERUN) {
-        EC_ERR("Writing EEPROMs only allowed in freerun mode!\n");
+    if (slave->master->mode != EC_MASTER_MODE_IDLE) {
+        EC_ERR("Writing EEPROMs only allowed in idle mode!\n");
         return -1;
     }
 
@@ -1351,38 +790,8 @@
 {
     ec_slave_t *slave = container_of(kobj, ec_slave_t, kobj);
 
-    if (attr == &attr_ring_position) {
-        return sprintf(buffer, "%i\n", slave->ring_position);
-    }
-    else if (attr == &attr_coupler_address) {
-        return sprintf(buffer, "%i:%i\n", slave->coupler_index,
-                       slave->coupler_subindex);
-    }
-    else if (attr == &attr_vendor_name) {
-        if (slave->type)
-            return sprintf(buffer, "%s\n", slave->type->vendor_name);
-    }
-    else if (attr == &attr_product_name) {
-        if (slave->type)
-            return sprintf(buffer, "%s\n", slave->type->product_name);
-    }
-    else if (attr == &attr_product_desc) {
-        if (slave->type)
-            return sprintf(buffer, "%s\n", slave->type->description);
-    }
-    else if (attr == &attr_sii_name) {
-        if (slave->eeprom_name)
-            return sprintf(buffer, "%s\n", slave->eeprom_name);
-    }
-    else if (attr == &attr_type) {
-        if (slave->type) {
-            if (slave->type->special == EC_TYPE_BUS_COUPLER)
-                return sprintf(buffer, "coupler\n");
-	    else if (slave->type->special == EC_TYPE_INFRA)
-                return sprintf(buffer, "infrastructure\n");
-            else
-                return sprintf(buffer, "normal\n");
-        }
+    if (attr == &attr_info) {
+        return ec_slave_info(slave, buffer);
     }
     else if (attr == &attr_state) {
         switch (slave->current_state) {
@@ -1460,38 +869,48 @@
 /*****************************************************************************/
 
 /**
-   \return size of sync manager contents
-*/
-
-size_t ec_slave_calc_sync_size(const ec_slave_t *slave, /**< EtherCAT slave */
-                               const ec_sync_t *sync /**< sync manager */
-                               )
-{
-    unsigned int i, found;
-    const ec_field_t *field;
-    const ec_varsize_t *var;
-    size_t size;
-
-    // if size is specified, return size
-    if (sync->size) return sync->size;
-
-    // sync manager has variable size (size == 0).
-
-    size = 0;
-    for (i = 0; (field = sync->fields[i]); i++) {
-        found = 0;
-        list_for_each_entry(var, &slave->varsize_fields, list) {
-            if (var->field != field) continue;
-            size += var->size;
-            found = 1;
-        }
-
-        if (!found) {
-            EC_WARN("Variable data field \"%s\" of slave %i has no size"
-                    " information!\n", field->name, slave->ring_position);
-        }
-    }
-    return size;
+   Calculates the size of a sync manager by evaluating PDO sizes.
+   \return sync manager size
+*/
+
+uint16_t ec_slave_calc_sync_size(const ec_slave_t *slave,
+                                 /**< EtherCAT slave */
+                                 const ec_sii_sync_t *sync
+                                 /**< sync manager */
+                                 )
+{
+    ec_sii_pdo_t *pdo;
+    ec_sii_pdo_entry_t *pdo_entry;
+    unsigned int bit_size;
+
+    if (sync->length) return sync->length;
+
+    bit_size = 0;
+    list_for_each_entry(pdo, &slave->sii_pdos, list) {
+        if (pdo->sync_index != sync->index) continue;
+
+        list_for_each_entry(pdo_entry, &pdo->entries, list) {
+            bit_size += pdo_entry->bit_length;
+        }
+    }
+
+    if (bit_size % 8) // round up to full bytes
+        return bit_size / 8 + 1;
+    else
+        return bit_size / 8;
+}
+
+/*****************************************************************************/
+
+/**
+   \return non-zero if slave is a bus coupler
+*/
+
+int ec_slave_is_coupler(const ec_slave_t *slave)
+{
+    // TODO: Better bus coupler criterion
+    return slave->sii_vendor_id == 0x00000002
+        && slave->sii_product_code == 0x044C2C52;
 }
 
 /******************************************************************************
@@ -1499,34 +918,23 @@
  *****************************************************************************/
 
 /**
-   Writes the "configured station alias" to the slave's EEPROM.
    \return 0 in case of success, else < 0
    \ingroup RealtimeInterface
 */
 
-int ecrt_slave_write_alias(ec_slave_t *slave, /**< EtherCAT slave */
-                           uint16_t alias /**< new alias */
-                           )
-{
-    return ec_slave_sii_write16(slave, 0x0004, alias);
-}
-
-/*****************************************************************************/
-
-/**
-   \return 0 in case of success, else < 0
-   \ingroup RealtimeInterface
-*/
-
-int ecrt_slave_field_size(ec_slave_t *slave, /**< EtherCAT slave */
-                          const char *field_name, /**< data field name */
-                          unsigned int field_index, /**< data field index */
-                          size_t size /**< new data field size */
-                          )
-{
+int ecrt_slave_pdo_size(ec_slave_t *slave, /**< EtherCAT slave */
+                        uint16_t pdo_index, /**< PDO index */
+                        uint8_t pdo_subindex, /**< PDO subindex */
+                        size_t size /**< new PDO size */
+                        )
+{
+    EC_WARN("ecrt_slave_pdo_size() currently not available.\n");
+    return -1;
+
+#if 0
     unsigned int i, j, field_counter;
-    const ec_sync_t *sync;
-    const ec_field_t *field;
+    const ec_sii_sync_t *sync;
+    const ec_pdo_t *pdo;
     ec_varsize_t *var;
 
     if (!slave->type) {
@@ -1574,14 +982,14 @@
            slave->ring_position, slave->type->vendor_name,
            slave->type->product_name, field_name, field_index);
     return -1;
+#endif
 }
 
 /*****************************************************************************/
 
 /**< \cond */
 
-EXPORT_SYMBOL(ecrt_slave_write_alias);
-EXPORT_SYMBOL(ecrt_slave_field_size);
+EXPORT_SYMBOL(ecrt_slave_pdo_size);
 
 /**< \endcond */
 
--- a/master/slave.h	Thu Jul 13 13:10:57 2006 +0000
+++ b/master/slave.h	Thu Aug 03 12:59:01 2006 +0000
@@ -44,9 +44,10 @@
 #include <linux/list.h>
 #include <linux/kobject.h>
 
+#include "../include/ecrt.h"
+
 #include "globals.h"
 #include "datagram.h"
-#include "types.h"
 
 /*****************************************************************************/
 
@@ -90,20 +91,6 @@
 /*****************************************************************************/
 
 /**
-   FMMU configuration.
-*/
-
-typedef struct
-{
-    const ec_domain_t *domain; /**< domain */
-    const ec_sync_t *sync; /**< sync manager */
-    uint32_t logical_start_address; /**< logical start address */
-}
-ec_fmmu_t;
-
-/*****************************************************************************/
-
-/**
    String object (EEPROM).
 */
 
@@ -113,7 +100,7 @@
     size_t size; /**< size in bytes */
     char *data; /**< string data */
 }
-ec_eeprom_string_t;
+ec_sii_string_t;
 
 /*****************************************************************************/
 
@@ -130,7 +117,7 @@
     uint8_t control_register; /**< control register value */
     uint8_t enable; /**< enable bit */
 }
-ec_eeprom_sync_t;
+ec_sii_sync_t;
 
 /*****************************************************************************/
 
@@ -143,7 +130,7 @@
     EC_RX_PDO, /**< Reveive PDO */
     EC_TX_PDO /**< Transmit PDO */
 }
-ec_pdo_type_t;
+ec_sii_pdo_type_t;
 
 /*****************************************************************************/
 
@@ -154,13 +141,13 @@
 typedef struct
 {
     struct list_head list; /**< list item */
-    ec_pdo_type_t type; /**< PDO type */
+    ec_sii_pdo_type_t type; /**< PDO type */
     uint16_t index; /**< PDO index */
-    uint8_t sync_manager; /**< assigned sync manager */
+    uint8_t sync_index; /**< assigned sync manager */
     char *name; /**< PDO name */
     struct list_head entries; /**< entry list */
 }
-ec_eeprom_pdo_t;
+ec_sii_pdo_t;
 
 /*****************************************************************************/
 
@@ -176,7 +163,7 @@
     char *name; /**< entry name */
     uint8_t bit_length; /**< entry length in bit */
 }
-ec_eeprom_pdo_entry_t;
+ec_sii_pdo_entry_t;
 
 /*****************************************************************************/
 
@@ -188,7 +175,6 @@
 {
     struct list_head list; /**< list item */
     uint16_t index; /**< SDO index */
-    //uint16_t type;
     uint8_t object_code; /**< object code */
     char *name; /**< SDO name */
     struct list_head entries; /**< entry list */
@@ -214,13 +200,27 @@
 /*****************************************************************************/
 
 /**
+   FMMU configuration.
+*/
+
+typedef struct
+{
+    const ec_domain_t *domain; /**< domain */
+    const ec_sii_sync_t *sync; /**< sync manager */
+    uint32_t logical_start_address; /**< logical start address */
+}
+ec_fmmu_t;
+
+/*****************************************************************************/
+
+/**
    Variable-sized field information.
 */
 
 typedef struct
 {
     struct list_head list; /**< list item */
-    const ec_field_t *field; /**< data field */
+    const ec_sii_pdo_t *pdo; /**< PDO */
     size_t size; /**< field size */
 }
 ec_varsize_t;
@@ -237,6 +237,12 @@
     struct kobject kobj; /**< kobject */
     ec_master_t *master; /**< master owning the slave */
 
+    ec_slave_state_t requested_state; /**< requested slave state */
+    ec_slave_state_t current_state; /**< current slave state */
+    unsigned int error_flag; /**< stop processing after an error */
+    unsigned int online; /**< non-zero, if the slave responds. */
+    uint8_t registered; /**< true, if slave has been registered */
+
     // addresses
     uint16_t ring_position; /**< ring position */
     uint16_t station_address; /**< configured station address */
@@ -255,6 +261,12 @@
     uint8_t dl_loop[4]; /**< loop closed */
     uint8_t dl_signal[4]; /**< detected signal on RX port */
 
+    // EEPROM
+    uint8_t *eeprom_data; /**< Complete EEPROM image */
+    uint16_t eeprom_size; /**< size of the EEPROM contents in byte */
+    uint16_t *new_eeprom_data; /**< new EEPROM data to write */
+    uint16_t new_eeprom_size; /**< size of new EEPROM data in words */
+
     // slave information interface
     uint16_t sii_alias; /**< configured station alias */
     uint32_t sii_vendor_id; /**< vendor id */
@@ -267,34 +279,19 @@
     uint16_t sii_tx_mailbox_size; /**< mailbox size (slave to master) */
     uint16_t sii_mailbox_protocols; /**< supported mailbox protocols */
     uint8_t sii_physical_layer[4]; /**< port media */
-
-    const ec_slave_type_t *type; /**< pointer to slave type object */
-
-    uint8_t registered; /**< true, if slave has been registered */
+    struct list_head sii_strings; /**< EEPROM STRING categories */
+    struct list_head sii_syncs; /**< EEPROM SYNC MANAGER categories */
+    struct list_head sii_pdos; /**< EEPROM [RT]XPDO categories */
+    char *sii_group; /**< slave group acc. to EEPROM */
+    char *sii_image; /**< slave image name acc. to EEPROM */
+    char *sii_order; /**< slave order number acc. to EEPROM */
+    char *sii_name; /**< slave name acc. to EEPROM */
 
     ec_fmmu_t fmmus[EC_MAX_FMMUS]; /**< FMMU configurations */
     uint8_t fmmu_count; /**< number of FMMUs used */
 
-    uint8_t *eeprom_data; /**< Complete EEPROM image */
-    uint16_t eeprom_size; /**< size of the EEPROM contents in byte */
-    struct list_head eeprom_strings; /**< EEPROM STRING categories */
-    struct list_head eeprom_syncs; /**< EEPROM SYNC MANAGER categories */
-    struct list_head eeprom_pdos; /**< EEPROM [RT]XPDO categories */
-    char *eeprom_group; /**< slave group acc. to EEPROM */
-    char *eeprom_image; /**< slave image name acc. to EEPROM */
-    char *eeprom_order; /**< slave order number acc. to EEPROM */
-    char *eeprom_name; /**< slave name acc. to EEPROM */
-
-    uint16_t *new_eeprom_data; /**< new EEPROM data to write */
-    size_t new_eeprom_size; /**< size of new EEPROM data in words */
-
     struct list_head sdo_dictionary; /**< SDO directory list */
 
-    ec_slave_state_t requested_state; /**< requested slave state */
-    ec_slave_state_t current_state; /**< current slave state */
-    unsigned int error_flag; /**< stop processing after an error */
-    unsigned int online; /**< non-zero, if the slave responds. */
-
     struct list_head varsize_fields; /**< size information for variable-sized
                                         data fields. */
 };
@@ -305,29 +302,27 @@
 int ec_slave_init(ec_slave_t *, ec_master_t *, uint16_t, uint16_t);
 void ec_slave_clear(struct kobject *);
 
-// slave control
-int ec_slave_fetch(ec_slave_t *);
-int ec_slave_sii_read16(ec_slave_t *, uint16_t, uint16_t *);
-int ec_slave_sii_read32(ec_slave_t *, uint16_t, uint32_t *);
-int ec_slave_sii_write16(ec_slave_t *, uint16_t, uint16_t);
-int ec_slave_state_change(ec_slave_t *, uint8_t);
 int ec_slave_prepare_fmmu(ec_slave_t *, const ec_domain_t *,
-                          const ec_sync_t *);
+                          const ec_sii_sync_t *);
 
 // CoE
-int ec_slave_fetch_sdo_list(ec_slave_t *);
-
-// state machine
+//int ec_slave_fetch_sdo_list(ec_slave_t *);
+
+// SII categories
 int ec_slave_fetch_strings(ec_slave_t *, const uint8_t *);
-int ec_slave_fetch_general(ec_slave_t *, const uint8_t *);
+void ec_slave_fetch_general(ec_slave_t *, const uint8_t *);
 int ec_slave_fetch_sync(ec_slave_t *, const uint8_t *, size_t);
-int ec_slave_fetch_pdo(ec_slave_t *, const uint8_t *, size_t, ec_pdo_type_t);
+int ec_slave_fetch_pdo(ec_slave_t *, const uint8_t *, size_t,
+                       ec_sii_pdo_type_t);
 int ec_slave_locate_string(ec_slave_t *, unsigned int, char **);
 
 // misc.
-size_t ec_slave_calc_sync_size(const ec_slave_t *, const ec_sync_t *);
+uint16_t ec_slave_calc_sync_size(const ec_slave_t *,
+                                 const ec_sii_sync_t *);
+
 void ec_slave_print(const ec_slave_t *, unsigned int);
-int ec_slave_check_crc(ec_slave_t *);
+int ec_slave_is_coupler(const ec_slave_t *);
+//int ec_slave_check_crc(ec_slave_t *);
 
 /*****************************************************************************/
 
--- a/master/types.c	Thu Jul 13 13:10:57 2006 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,280 +0,0 @@
-/******************************************************************************
- *
- *  $Id$
- *
- *  Copyright (C) 2006  Florian Pose, Ingenieurgemeinschaft IgH
- *
- *  This file is part of the IgH EtherCAT Master.
- *
- *  The IgH EtherCAT Master is free software; you can redistribute it
- *  and/or modify it under the terms of the GNU General Public License
- *  as published by the Free Software Foundation; either version 2 of the
- *  License, or (at your option) any later version.
- *
- *  The IgH EtherCAT Master 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.
- *
- *  You should have received a copy of the GNU General Public License
- *  along with the IgH EtherCAT Master; if not, write to the Free Software
- *  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
- *
- *  The right to use EtherCAT Technology is granted and comes free of
- *  charge under condition of compatibility of product made by
- *  Licensee. People intending to distribute/sell products based on the
- *  code, have to sign an agreement to guarantee that products using
- *  software based on IgH EtherCAT master stay compatible with the actual
- *  EtherCAT specification (which are released themselves as an open
- *  standard) as the (only) precondition to have the right to use EtherCAT
- *  Technology, IP and trade marks.
- *
- *****************************************************************************/
-
-/**
-   \file
-   EtherCAT slave descriptions.
-   \cond
-*/
-
-/*****************************************************************************/
-
-#include <linux/module.h>
-
-#include "globals.h"
-#include "types.h"
-
-/*****************************************************************************/
-
-const ec_sync_t mailbox_sm0 = {0x1800, 246, 0x26, {NULL}};
-const ec_sync_t mailbox_sm1 = {0x18F6, 246, 0x22, {NULL}};
-
-/******************************************************************************
- *  slave objects
- *****************************************************************************/
-
-const ec_slave_type_t Beckhoff_EK1100 = {
-    "Beckhoff", "EK1100", "Bus Coupler", EC_TYPE_BUS_COUPLER,
-    {NULL} // no sync managers
-};
-
-/*****************************************************************************/
-
-const ec_slave_type_t Beckhoff_EK1110 = {
-    "Beckhoff", "EK1110", "Extension terminal", EC_TYPE_INFRA,
-    {NULL} // no sync managers
-};
-
-/*****************************************************************************/
-
-const ec_field_t bk1120_out = {"Outputs", 0}; // variable size
-const ec_field_t bk1120_in = {"Inputs", 0}; // variable size
-
-const ec_sync_t bk1120_sm0 = {0x1C00, 264, 0x26, {NULL}};
-const ec_sync_t bk1120_sm1 = {0x1E00, 264, 0x22, {NULL}};
-
-const ec_sync_t bk1120_sm2 = { // outputs
-    0x1000, 0, 0x24, // variable size
-    {&bk1120_out, NULL}
-};
-
-const ec_sync_t bk1120_sm3 = { // inputs
-    0x1600, 0, 0x00, // variable size
-    {&bk1120_in, NULL}
-};
-
-const ec_slave_type_t Beckhoff_BK1120 = {
-    "Beckhoff", "BK1120", "KBUS Coupler", EC_TYPE_NORMAL,
-    {&bk1120_sm0, &bk1120_sm1, &bk1120_sm2, &bk1120_sm3, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el1004_in = {"InputValue", 1};
-
-const ec_sync_t el1004_sm0 = { // inputs
-    0x1000, 1, 0x00,
-    {&el1004_in, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL1004 = {
-    "Beckhoff", "EL1004", "4x Digital Input, 3ms", EC_TYPE_NORMAL,
-    {&el1004_sm0, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el1014_in = {"InputValue", 1};
-
-const ec_sync_t el1014_sm0 = { // inputs
-    0x1000, 1, 0x00,
-    {&el1014_in, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL1014 = {
-    "Beckhoff", "EL1014", "4x Digital Input, 10us", EC_TYPE_NORMAL,
-    {&el1014_sm0, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el20XX_out = {"OutputValue", 1};
-
-const ec_sync_t el20XX_sm0 = {
-    0x0F00, 1, 0x46,
-    {&el20XX_out, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL2004 = {
-    "Beckhoff", "EL2004", "4x Digital Output", EC_TYPE_NORMAL,
-    {&el20XX_sm0, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL2032 = {
-    "Beckhoff", "EL2032", "2x Digital Output (2A)", EC_TYPE_NORMAL,
-    {&el20XX_sm0, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el31X2_st1 = {"Status",     1};
-const ec_field_t el31X2_ip1 = {"InputValue", 2};
-const ec_field_t el31X2_st2 = {"Status",     1};
-const ec_field_t el31X2_ip2 = {"InputValue", 2};
-
-const ec_sync_t el31X2_sm2 = {0x1000, 4, 0x24, {NULL}};
-
-const ec_sync_t el31X2_sm3 = {
-    0x1100, 6, 0x20,
-    {&el31X2_st1, &el31X2_ip1, &el31X2_st2, &el31X2_ip2, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL3102 = {
-    "Beckhoff", "EL3102", "2x Analog Input diff.", EC_TYPE_NORMAL,
-    {&mailbox_sm0, &mailbox_sm1, &el31X2_sm2, &el31X2_sm3, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL3162 = {
-    "Beckhoff", "EL3162", "2x Analog Input", EC_TYPE_NORMAL,
-    {&mailbox_sm0, &mailbox_sm1, &el31X2_sm2, &el31X2_sm3, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el41X2_op = {"OutputValue", 2};
-
-const ec_sync_t el41X2_sm2 = {
-    0x1000, 4, 0x24,
-    {&el41X2_op, &el41X2_op, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL4102 = {
-    "Beckhoff", "EL4102", "2x Analog Output", EC_TYPE_NORMAL,
-    {&mailbox_sm0, &mailbox_sm1, &el41X2_sm2, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL4132 = {
-    "Beckhoff", "EL4132", "2x Analog Output diff.", EC_TYPE_NORMAL,
-    {&mailbox_sm0, &mailbox_sm1, &el41X2_sm2, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el5001_st = {"Status",     1};
-const ec_field_t el5001_ip = {"InputValue", 4};
-
-const ec_sync_t el5001_sm2 = {
-    0x1000, 4, 0x24,
-    {NULL}
-};
-
-const ec_sync_t el5001_sm3 = {
-    0x1100, 5, 0x20,
-    {&el5001_st, &el5001_ip, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL5001 = {
-    "Beckhoff", "EL5001", "SSI-Interface", EC_TYPE_NORMAL,
-    {&mailbox_sm0, &mailbox_sm1, &el5001_sm2, &el5001_sm3, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t el5101_ct = {"Control",     1};
-const ec_field_t el5101_op = {"OutputValue", 2};
-const ec_field_t el5101_st = {"Status",      1};
-const ec_field_t el5101_ip = {"InputValue",  2};
-const ec_field_t el5101_la = {"LatchValue",  2};
-
-const ec_sync_t el5101_sm2 = {
-    0x1000, 3, 0x24,
-    {&el5101_ct, &el5101_op, NULL}
-};
-
-const ec_sync_t el5101_sm3 = {
-    0x1100, 5, 0x20,
-    {&el5101_st, &el5101_ip, &el5101_la, NULL}
-};
-
-const ec_slave_type_t Beckhoff_EL5101 = {
-    "Beckhoff", "EL5101", "Incremental Encoder Interface", EC_TYPE_NORMAL,
-    {&mailbox_sm0, &mailbox_sm1, &el5101_sm2, &el5101_sm3, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_sync_t el6601_sm0 = {0x1800, 522, 0x26, {NULL}};
-const ec_sync_t el6601_sm1 = {0x1C00, 522, 0x22, {NULL}};
-
-const ec_slave_type_t Beckhoff_EL6601 = {
-    "Beckhoff", "EL6601", "1-Port Ethernet Switch Terminal", EC_TYPE_EOE,
-    {&el6601_sm0, &el6601_sm1, NULL, NULL, NULL}
-};
-
-/*****************************************************************************/
-
-const ec_field_t trlinenc2_st = {"Status",     1};
-const ec_field_t trlinenc2_ip = {"InputValue", 4};
-
-const ec_sync_t trlinenc2_sm0 = {0x1800, 192, 0x26, {NULL}};
-const ec_sync_t trlinenc2_sm1 = {0x1C00, 192, 0x22, {NULL}};
-const ec_sync_t trlinenc2_sm2 = {0x1000,   4, 0x24, {NULL}};
-
-const ec_sync_t trlinenc2_sm3 = {
-    0x1100, 5, 0x20,
-    {&trlinenc2_st, &trlinenc2_ip, NULL}
-};
-
-const ec_slave_type_t TR_Electronic_LinEnc2 = {
-    "TR-Electronic", "LinEnc2", "SSI-Encoder", EC_TYPE_NORMAL,
-    {&trlinenc2_sm0, &trlinenc2_sm1, &trlinenc2_sm2, &trlinenc2_sm3, NULL}
-};
-
-/** \endcond */
-
-/*****************************************************************************/
-
-/**
-   Mapping between vendor IDs and product codes <=> slave objects.
-*/
-
-ec_slave_ident_t slave_idents[] = {
-    {0x00000002, 0x03EC3052, &Beckhoff_EL1004},
-    {0x00000002, 0x03F63052, &Beckhoff_EL1014},
-    {0x00000002, 0x044C2C52, &Beckhoff_EK1100},
-    {0x00000002, 0x04562C52, &Beckhoff_EK1110},
-    {0x00000002, 0x04602C22, &Beckhoff_BK1120},
-    {0x00000002, 0x07D43052, &Beckhoff_EL2004},
-    {0x00000002, 0x07F03052, &Beckhoff_EL2032},
-    {0x00000002, 0x0C1E3052, &Beckhoff_EL3102},
-    {0x00000002, 0x0C5A3052, &Beckhoff_EL3162},
-    {0x00000002, 0x10063052, &Beckhoff_EL4102},
-    {0x00000002, 0x10243052, &Beckhoff_EL4132},
-    {0x00000002, 0x13893052, &Beckhoff_EL5001},
-    {0x00000002, 0x13ED3052, &Beckhoff_EL5101},
-    {0x00000002, 0x19C93052, &Beckhoff_EL6601},
-    {0x000000D4, 0x00000017, &TR_Electronic_LinEnc2},
-    {}
-};
-
-/*****************************************************************************/
--- a/master/types.h	Thu Jul 13 13:10:57 2006 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,130 +0,0 @@
-/******************************************************************************
- *
- *  $Id$
- *
- *  Copyright (C) 2006  Florian Pose, Ingenieurgemeinschaft IgH
- *
- *  This file is part of the IgH EtherCAT Master.
- *
- *  The IgH EtherCAT Master is free software; you can redistribute it
- *  and/or modify it under the terms of the GNU General Public License
- *  as published by the Free Software Foundation; either version 2 of the
- *  License, or (at your option) any later version.
- *
- *  The IgH EtherCAT Master 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.
- *
- *  You should have received a copy of the GNU General Public License
- *  along with the IgH EtherCAT Master; if not, write to the Free Software
- *  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
- *
- *  The right to use EtherCAT Technology is granted and comes free of
- *  charge under condition of compatibility of product made by
- *  Licensee. People intending to distribute/sell products based on the
- *  code, have to sign an agreement to guarantee that products using
- *  software based on IgH EtherCAT master stay compatible with the actual
- *  EtherCAT specification (which are released themselves as an open
- *  standard) as the (only) precondition to have the right to use EtherCAT
- *  Technology, IP and trade marks.
- *
- *****************************************************************************/
-
-/**
-   \file
-   EtherCAT slave types.
-*/
-
-/*****************************************************************************/
-
-#ifndef _EC_TYPES_H_
-#define _EC_TYPES_H_
-
-#include <linux/types.h>
-
-#include "../include/ecrt.h"
-
-/*****************************************************************************/
-
-#define EC_MAX_FIELDS 10 /**< maximal number of data fields per sync manager */
-#define EC_MAX_SYNC   16 /**< maximal number of sync managers per type */
-
-/*****************************************************************************/
-
-/**
-   Special slaves.
-*/
-
-typedef enum
-{
-    EC_TYPE_NORMAL, /**< no special slave */
-    EC_TYPE_BUS_COUPLER, /**< slave is a bus coupler */
-    EC_TYPE_INFRA, /**< infrastructure slaves, that contain no process data */
-    EC_TYPE_EOE /**< slave is an EoE switch */
-}
-ec_special_type_t;
-
-/*****************************************************************************/
-
-/**
-   Process data field.
-*/
-
-typedef struct
-{
-    const char *name; /**< field name */
-    size_t size; /**< field size in bytes */
-}
-ec_field_t;
-
-/*****************************************************************************/
-
-/**
-   Sync manager.
-*/
-
-typedef struct
-{
-    uint16_t physical_start_address; /**< physical start address */
-    uint16_t size; /**< size in bytes */
-    uint8_t control_byte; /**< control register value */
-    const ec_field_t *fields[EC_MAX_FIELDS]; /**< field array */
-}
-ec_sync_t;
-
-/*****************************************************************************/
-
-/**
-   Slave description type.
-*/
-
-typedef struct ec_slave_type
-{
-    const char *vendor_name; /**< vendor name*/
-    const char *product_name; /**< product name */
-    const char *description; /**< free description */
-    ec_special_type_t special; /**< special slave type? */
-    const ec_sync_t *sync_managers[EC_MAX_SYNC]; /**< sync managers */
-}
-ec_slave_type_t;
-
-/*****************************************************************************/
-
-/**
-   Slave type identification.
-*/
-
-typedef struct
-{
-    uint32_t vendor_id; /**< vendor id */
-    uint32_t product_code; /**< product code */
-    const ec_slave_type_t *type; /**< associated slave description object */
-}
-ec_slave_ident_t;
-
-extern ec_slave_ident_t slave_idents[]; /**< array with slave descriptions */
-
-/*****************************************************************************/
-
-#endif
--- a/script/ec_list.pl	Thu Jul 13 13:10:57 2006 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,192 +0,0 @@
-#!/usr/bin/perl
-
-#------------------------------------------------------------------------------
-#
-#  e c _ l i s t . p l
-#
-#  Userspace tool for listing EtherCAT slaves.
-#
-#  $Id$
-#
-#  Copyright (C) 2006  Florian Pose, Ingenieurgemeinschaft IgH
-#
-#  This file is part of the IgH EtherCAT Master.
-#
-#  The IgH EtherCAT Master is free software; you can redistribute it
-#  and/or modify it under the terms of the GNU General Public License
-#  as published by the Free Software Foundation; either version 2 of the
-#  License, or (at your option) any later version.
-#
-#  The IgH EtherCAT Master 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.
-#
-#  You should have received a copy of the GNU General Public License
-#  along with the IgH EtherCAT Master; if not, write to the Free Software
-#  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
-#
-#  The right to use EtherCAT Technology is granted and comes free of
-#  charge under condition of compatibility of product made by
-#  Licensee. People intending to distribute/sell products based on the
-#  code, have to sign an agreement to guarantee that products using
-#  software based on IgH EtherCAT master stay compatible with the actual
-#  EtherCAT specification (which are released themselves as an open
-#  standard) as the (only) precondition to have the right to use EtherCAT
-#  Technology, IP and trade marks.
-#
-#------------------------------------------------------------------------------
-
-use strict;
-use Getopt::Std;
-
-my $master_index;
-my $master_dir;
-my $show_sii_naming;
-
-#------------------------------------------------------------------------------
-
-&get_options;
-&query_master;
-exit 0;
-
-#------------------------------------------------------------------------------
-
-sub query_master
-{
-    $master_dir = "/sys/ethercat" . $master_index;
-    &query_slaves;
-}
-
-#------------------------------------------------------------------------------
-
-sub query_slaves
-{
-    my $dirhandle;
-    my $slave_dir;
-    my $entry;
-    my $slave_index;
-    my $file_name;
-    my $vendor_name;
-    my @slaves;
-    my $slave;
-    my $abs;
-
-    unless (opendir $dirhandle, $master_dir) {
-	print "Failed to open directory \"$master_dir\".\n";
-	exit 1;
-    }
-
-    while ($entry = readdir $dirhandle) {
-        next unless $entry =~ /^slave(\d+)$/;
-	$slave_dir = $master_dir . "/" . $entry;
-
-	$slave = {};
-	$slave->{'ring_position'} =
-	    &read_integer("$slave_dir/ring_position");
-	$slave->{'coupler_address'} =
-	    &read_string("$slave_dir/coupler_address");
-	unless ($show_sii_naming) {
-	    $slave->{'vendor_name'} =
-		&read_string("$slave_dir/vendor_name");
-	    $slave->{'product_name'} =
-		&read_string("$slave_dir/product_name");
-	    $slave->{'product_desc'} =
-		&read_string("$slave_dir/product_desc");
-	}
-	else {
-	    $slave->{'sii_name'} =
-		&read_string("$slave_dir/sii_name");
-	}
-	$slave->{'type'} =
-	    &read_string("$slave_dir/type");
-
-	push @slaves, $slave;
-    }
-    closedir $dirhandle;
-
-    @slaves = sort { $a->{'ring_position'} <=> $b->{'ring_position'} } @slaves;
-
-    print "EtherCAT bus listing for master $master_index:\n";
-    for $slave (@slaves) {
-	if ($slave->{'type'} eq "coupler") {
-	    print "--------------------------------------------------------\n";
-	}
-
-	$abs = sprintf "%i", $slave->{'ring_position'};
-	printf(" %3s %8s   ", $abs, $slave->{'coupler_address'});
-	unless ($show_sii_naming) {
-	    printf("%-12s %-10s %s\n", $slave->{'vendor_name'},
-		   $slave->{'product_name'}, $slave->{'product_desc'});
-	}
-	else {
-	    printf("%s\n", $slave->{'sii_name'});
-	}
-    }
-}
-
-#------------------------------------------------------------------------------
-
-sub read_string
-{
-    (my $file_name) = @_;
-    my $data;
-
-    $data = `cat $file_name 2>/dev/null`;
-    if ($?) {
-	print "ERROR: Unable to read string $file_name!\n";
-	exit 1;
-    }
-
-    chomp $data;
-    return $data;
-}
-
-#------------------------------------------------------------------------------
-
-sub read_integer
-{
-    (my $file_name) = @_;
-
-    if (`cat $file_name 2>/dev/null` !~ /^(\d+)$/) {
-	print "ERROR: Unable to read integer $file_name!\n";
-	exit 1;
-    }
-
-    return int $1;
-}
-
-#------------------------------------------------------------------------------
-
-sub get_options
-{
-    my %opt;
-    my $optret;
-
-    $optret = getopts "m:sh", \%opt;
-
-    &print_usage if defined $opt{'h'} or $#ARGV > -1 or !$optret;
-
-    if (defined $opt{'m'}) {
-	$master_index = $opt{'m'};
-    }
-    else {
-	$master_index = 0;
-    }
-
-    $show_sii_naming = defined $opt{'s'};
-}
-
-#------------------------------------------------------------------------------
-
-sub print_usage
-{
-    print "Usage: ec_list [OPTIONS]\n";
-    print "        -m <IDX>    Query master <IDX>.\n";
-    print "        -s          Show SII naming instead of";
-    print " vendor/product/description.\n";
-    print "        -h          Show this help.\n";
-    exit 0;
-}
-
-#------------------------------------------------------------------------------
--- a/script/ethercat.sh	Thu Jul 13 13:10:57 2006 +0000
+++ b/script/ethercat.sh	Thu Aug 03 12:59:01 2006 +0000
@@ -38,9 +38,9 @@
 ### BEGIN INIT INFO
 # Provides:          ethercat
 # Required-Start:    $local_fs $syslog $network
-# Should-Start:      $time
+# Should-Start:      $time ntp
 # Required-Stop:     $local_fs $syslog $network
-# Should-Stop:       $time
+# Should-Stop:       $time ntp
 # Default-Start:     3 5
 # Default-Stop:      0 1 2 6
 # Short-Description: IgH EtherCAT master modules
@@ -51,9 +51,14 @@
 
 ETHERCAT_CONFIG=/etc/sysconfig/ethercat
 
-test -r $ETHERCAT_CONFIG || { echo "$ETHERCAT_CONFIG not existing";
-	if [ "$1" = "stop" ]; then exit 0;
-	else exit 6; fi; }
+if [ ! -r $ETHERCAT_CONFIG ]; then
+	echo "$ETHERCAT_CONFIG not existing";
+	if [ "$1" = "stop" ]; then
+		exit 0
+	else
+		exit 6
+	fi
+fi
 
 . $ETHERCAT_CONFIG
 
@@ -62,35 +67,36 @@
 #
 #  Function for setting up the EoE bridge
 #
-build_eoe_bridge() {
-        if [ -z "$EOE_BRIDGE" ]; then return; fi
-
-	EOE_INTERFACES=`/sbin/ifconfig -a | grep -o -E "^eoe[0-9]+ "`
+build_eoe_bridge()
+{
+	if [ -z "$EOE_BRIDGE" ]; then return; fi
+
+	EOEIF=`/sbin/ifconfig -a | grep -o -E "^eoe[0-9]+ "`
 
 	# add bridge, if it does not already exist
 	if ! /sbin/brctl show | grep -E -q "^$EOE_BRIDGE"; then
-	        if ! /sbin/brctl addbr $EOE_BRIDGE; then
-		        /bin/false
-			rc_status -v
-			rc_exit
-		fi
-	fi
-
-       	# check if specified interfaces are bridged
-	for interf in $EOE_INTERFACES $EOE_EXTRA_INTERFACES; do
-	        # interface is already part of the bridge 
-	        if /sbin/brctl show $EOE_BRIDGE | grep -E -q $interf
-		        then continue
+		if ! /sbin/brctl addbr $EOE_BRIDGE; then
+			/bin/false
+			rc_status -v
+			rc_exit
+		fi
+	fi
+
+    # check if specified interfaces are bridged
+	for interf in $EOEIF $EOE_EXTRA_INTERFACES; do
+	    # interface is already part of the bridge
+		if /sbin/brctl show $EOE_BRIDGE | grep -E -q $interf
+			then continue
 		fi
 		# clear IP address and open interface
 		if ! /sbin/ifconfig $interf 0.0.0.0 up; then
-		        /bin/false
+			/bin/false
 			rc_status -v
 			rc_exit
 		fi
 		# add interface to the bridge
 		if ! /sbin/brctl addif $EOE_BRIDGE $interf; then
-		        /bin/false
+			/bin/false
 			rc_status -v
 			rc_exit
 		fi
@@ -98,9 +104,9 @@
 
 	# configure IP on bridge
 	if [ -n "$EOE_IP_ADDRESS" -a -n "$EOE_IP_NETMASK" ]; then
-	        if ! /sbin/ifconfig $EOE_BRIDGE $EOE_IP_ADDRESS \
-		        netmask $EOE_IP_NETMASK; then
-		        /bin/false
+		if ! /sbin/ifconfig $EOE_BRIDGE $EOE_IP_ADDRESS \
+			netmask $EOE_IP_NETMASK; then
+			/bin/false
 			rc_status -v
 			rc_exit
 		fi
@@ -108,23 +114,23 @@
 
 	# open bridge
 	if ! /sbin/ifconfig $EOE_BRIDGE up; then
-	        /bin/false
+		/bin/false
 		rc_status -v
 		rc_exit
 	fi
 
 	# install new default gateway
 	if [ -n "$EOE_GATEWAY" ]; then
-	        while /sbin/route -n | grep -E -q "^0.0.0.0"; do
-		        if ! /sbin/route del default; then
-			        echo "Failed to remove route!" 1>&2
+		while /sbin/route -n | grep -E -q "^0.0.0.0"; do
+			if ! /sbin/route del default; then
+				echo "Failed to remove route!" 1>&2
 				/bin/false
 				rc_status -v
 				rc_exit
 			fi
 		done
 		if ! /sbin/route add default gw $EOE_GATEWAY; then
-		        /bin/false
+			/bin/false
 			rc_status -v
 			rc_exit
 		fi
@@ -137,106 +143,116 @@
 rc_reset
 
 case "$1" in
+
     start)
-	echo -n "Starting EtherCAT master "
-
-	if [ -z "$DEVICE_INDEX" ]; then
-	    echo "ERROR: DEVICE_INDEX not set!"
-	    /bin/false
-	    rc_status -v
-	    rc_exit
-	fi
-
-	if [ -z "$EOE_DEVICES" ]; then
-	    EOE_DEVICES=0
-	fi
-
-	# unload conflicting modules at first
-	for mod in 8139too 8139cp; do
-		if lsmod | grep "^$mod " > /dev/null; then
-			if ! rmmod $mod; then
-				/bin/false
-				rc_status -v
-				rc_exit
+		echo -n "Starting EtherCAT master "
+
+		if [ -z "$DEVICE_INDEX" ]; then
+			echo "ERROR: DEVICE_INDEX not set!"
+			/bin/false
+			rc_status -v
+			rc_exit
+		fi
+
+		if [ -z "$EOE_INTERFACES" ]; then
+			if [ -n "$EOE_DEVICES" ]; then # support legacy sysconfig files
+				EOE_INTERFACES=$EOE_DEVICES
+			else
+				EOE_INTERFACES=0
 			fi
 		fi
-	done
-
-	# load master module
-	if ! modprobe ec_master ec_eoe_devices=$EOE_DEVICES; then
-	    /bin/false
-	    rc_status -v
-	    rc_exit
-	fi
-
-	# load device module
-	if ! modprobe ec_8139too ec_device_index=$DEVICE_INDEX; then
-	    /bin/false
-	    rc_status -v
-	    rc_exit
-	fi
-
-	# build EoE bridge
-	build_eoe_bridge
-
-	rc_status -v
-	;;
+
+	    # unload conflicting modules at first
+		for mod in 8139too; do
+			if lsmod | grep "^$mod " > /dev/null; then
+				if ! rmmod $mod; then
+					/bin/false
+					rc_status -v
+					rc_exit
+				fi
+			fi
+		done
+
+	    # load master module
+		if ! modprobe ec_master ec_eoeif_count=$EOE_INTERFACES; then
+			modprobe 8139too
+			/bin/false
+			rc_status -v
+			rc_exit
+		fi
+
+        # load device module
+		if ! modprobe ec_8139too ec_device_index=$DEVICE_INDEX; then
+			rmmod ec_master
+			modprobe 8139too
+			/bin/false
+			rc_status -v
+			rc_exit
+		fi
+
+        # build EoE bridge
+		build_eoe_bridge
+
+		rc_status -v
+		;;
 
     stop)
-	echo -n "Shutting down EtherCAT master "
-
-	# unload modules
-	for mod in ec_8139too ec_master; do
-		if lsmod | grep "^$mod " > /dev/null; then
-			if ! rmmod $mod; then
-				/bin/false
-				rc_status -v
-				rc_exit
+		echo -n "Shutting down EtherCAT master "
+
+	    # unload modules
+		for mod in ec_8139too ec_master; do
+			if lsmod | grep "^$mod " > /dev/null; then
+				if ! rmmod $mod; then
+					/bin/false
+					rc_status -v
+					rc_exit
+				fi;
 			fi;
-		fi;
-	done
-
-	# reload previous modules
-	if ! modprobe 8139too; then
-	    echo "Warning: Failed to restore 8139too module."
-	fi
-
-	rc_status -v
-	;;
+		done
+
+		sleep 1
+
+	    # reload previous modules
+		if ! modprobe 8139too; then
+			echo "Warning: Failed to restore 8139too module."
+		fi
+
+		rc_status -v
+		;;
 
     restart)
-	$0 stop || exit 1
-	$0 start
-
-	rc_status
-	;;
+		$0 stop || exit 1
+		sleep 1
+		$0 start
+		rc_status
+		;;
 
     status)
-	echo -n "Checking for EtherCAT "
-
-	lsmod | grep "^ec_master " > /dev/null
-	master_running=$?
-	lsmod | grep "^ec_8139too " > /dev/null
-	device_running=$?
-
-	# master module and device module loaded?
-	test $master_running -eq 0 -a $device_running -eq 0
-
-	rc_status -v
-	;;
+		echo -n "Checking for EtherCAT "
+
+		lsmod | grep "^ec_master " > /dev/null
+		master_running=$?
+		lsmod | grep "^ec_8139too " > /dev/null
+		device_running=$?
+
+	    # master module and device module loaded?
+		test $master_running -eq 0 -a $device_running -eq 0
+
+		rc_status -v
+		;;
 
     bridge)
-	echo -n "Building EoE bridge "
-
-	build_eoe_bridge
-
-	rc_status -v
-	;;
+		echo -n "Building EoE bridge "
+		build_eoe_bridge
+		rc_status -v
+		;;
 
     *)
-	echo "USAGE: $0 {start|stop|restart|status|bridge}"
-	;;
+		echo "USAGE: $0 {start|stop|restart|status|bridge}"
+		;;
+
 esac
+
 rc_exit
 
 #------------------------------------------------------------------------------
--- a/script/install.sh	Thu Jul 13 13:10:57 2006 +0000
+++ b/script/install.sh	Thu Aug 03 12:59:01 2006 +0000
@@ -88,8 +88,10 @@
 # Install tools
 
 echo "  Installing tools"
-cp script/ec_list.pl /usr/local/bin/ec_list || exit 1
+cp script/lsec.pl /usr/local/bin/lsec || exit 1
 chmod +x /usr/local/bin/ec_list || exit 1
+rm -f /usr/local/bin/ec_list || exit 1
+ln -s /usr/local/bin/lsec /usr/local/bin/ec_list || exit 1
 
 #------------------------------------------------------------------------------
 
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/script/lsec.pl	Thu Aug 03 12:59:01 2006 +0000
@@ -0,0 +1,147 @@
+#!/usr/bin/perl
+
+#------------------------------------------------------------------------------
+#
+#  l s e c  -  List EtherCAT
+#
+#  Userspace tool for listing EtherCAT slaves.
+#
+#  $Id$
+#
+#  Copyright (C) 2006  Florian Pose, Ingenieurgemeinschaft IgH
+#
+#  This file is part of the IgH EtherCAT Master.
+#
+#  The IgH EtherCAT Master is free software; you can redistribute it
+#  and/or modify it under the terms of the GNU General Public License
+#  as published by the Free Software Foundation; either version 2 of the
+#  License, or (at your option) any later version.
+#
+#  The IgH EtherCAT Master 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.
+#
+#  You should have received a copy of the GNU General Public License
+#  along with the IgH EtherCAT Master; if not, write to the Free Software
+#  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+#
+#  The right to use EtherCAT Technology is granted and comes free of
+#  charge under condition of compatibility of product made by
+#  Licensee. People intending to distribute/sell products based on the
+#  code, have to sign an agreement to guarantee that products using
+#  software based on IgH EtherCAT master stay compatible with the actual
+#  EtherCAT specification (which are released themselves as an open
+#  standard) as the (only) precondition to have the right to use EtherCAT
+#  Technology, IP and trade marks.
+#
+#------------------------------------------------------------------------------
+
+use strict;
+use Getopt::Std;
+
+my $master_index;
+my $master_dir;
+
+#------------------------------------------------------------------------------
+
+&get_options;
+&query_master;
+exit 0;
+
+#------------------------------------------------------------------------------
+
+sub query_master
+{
+    $master_dir = "/sys/ethercat" . $master_index;
+    &query_slaves;
+}
+
+#------------------------------------------------------------------------------
+
+sub query_slaves
+{
+    my $dirhandle;
+    my $entry;
+    my @slaves;
+    my $slave;
+    my $abs;
+	my $line;
+
+    unless (opendir $dirhandle, $master_dir) {
+		print "Failed to open directory \"$master_dir\".\n";
+		exit 1;
+    }
+
+    while ($entry = readdir $dirhandle) {
+        next unless $entry =~ /^slave(\d+)$/;
+
+		$slave = {};
+
+		open INFO, "$master_dir/$entry/info" or die
+			"ERROR: Failed to open $master_dir/$entry/info";
+
+		while ($line = <INFO>) {
+			if ($line =~ /^Name: (.*)$/) {
+				$slave->{'name'} = $1;
+			}
+			elsif ($line =~ /^Ring position: (\d+)$/) {
+				$slave->{'ring_position'} = $1;
+			}
+			elsif ($line =~ /^Advanced position: (\d+:\d+)$/) {
+				$slave->{'advanced_position'} = $1;
+			}
+			elsif ($line =~ /^State: (.+)$/) {
+				$slave->{'state'} = $1;
+			}
+		}
+
+		close INFO;
+
+		push @slaves, $slave;
+    }
+    closedir $dirhandle;
+
+    @slaves = sort { $a->{'ring_position'} <=> $b->{'ring_position'} } @slaves;
+
+    print "EtherCAT bus listing for master $master_index:\n";
+    for $slave (@slaves) {
+		$abs = sprintf "%i", $slave->{'ring_position'};
+		printf(" %3s %8s  %-6s  %s\n",
+			   $abs, $slave->{'advanced_position'},
+			   $slave->{'state'}, $slave->{'name'});
+    }
+}
+
+#------------------------------------------------------------------------------
+
+sub get_options
+{
+    my %opt;
+    my $optret;
+
+    $optret = getopts "m:h", \%opt;
+
+    &print_usage if defined $opt{'h'} or $#ARGV > -1 or !$optret;
+
+    if (defined $opt{'m'}) {
+		$master_index = $opt{'m'};
+    }
+    else {
+		$master_index = 0;
+    }
+}
+
+#------------------------------------------------------------------------------
+
+sub print_usage
+{
+	my $cmd = `basename $0`;
+	chomp $cmd;
+    print "Usage: $cmd [OPTIONS]\n";
+    print "        -m <IDX>    Query master <IDX>.\n";
+    print "        -h          Show this help.\n";
+    exit 0;
+}
+
+#------------------------------------------------------------------------------
--- a/script/sysconfig	Thu Jul 13 13:10:57 2006 +0000
+++ b/script/sysconfig	Thu Aug 03 12:59:01 2006 +0000
@@ -13,10 +13,10 @@
 #DEVICE_INDEX=99
 
 #
-#  Number of Ethernet-over-EtherCAT devices every master shall create
+#  Number of Ethernet-over-EtherCAT interfaces every master shall create
 #  on startup. Default is 0.
 #
-#EOE_DEVICES=0
+#EOE_INTERFACES=0
 
 #
 #  Bridge all EoE interfaces after master startup