OpenEtherCATsociety / SOEM

Simple Open Source EtherCAT Master
Other
1.35k stars 684 forks source link

Invalid DC SYNC configuration #142

Closed satishdamo closed 6 years ago

satishdamo commented 6 years ago

Dear sir, Please guide me to correct "Invalid DC SYNC configuration " error in Beckhoff Ethercat encoder interface terminal , i am using SOEM master function, ec_configdc() and ec_sync (user function in redtest). Please let me know what's the cause of this error and how to rectify this.

mheden commented 6 years ago

You are probably missing something regarding the slave configuration. Please refer to the commissioning part of the manual for your slave to see what needs to be done.

tecodrive commented 6 years ago

I solved this problem with EL5101.

SOEM is set slaves after ec_config_map() to SAFE_OP. EL5101 take ec_dcsync0() only in PRE_OP.

FIRST look to my patch, that avoid slaves goes to SAFE_OP after ec_config_map().

You can set slaves to SAFE_OP yourself later with ... ec_slave[ 0 ].state = EC_STATE_SAFE_OP; ec_writestate( 0 );

With my PATCH, you can call in PRE_OP ec_configdc(). After that immediately (<100ms) you call ec_dcsync0( slave , ...), that start the SYNC0 Impuls in the future ...

Look at ecx_dcsync0() in ethercatdc.c t = ((t1 + SyncDelay) / CyclTime) * CyclTime + CyclTime + CyclShift;

with my words ... t1 ~ ec_DCtime SYNC0_start_time = ((ec_DCtime + SyncDelay /100ms/) / CyclTime) * CyclTime + CyclTime + CyclShift;

After that, set slaves to SAFE_OP, than start you realtime task. Wait minium 1s. The EL5101 will sync the PLL.

Your realtime task Master-PLL should look like ... it syncronize to modulo of cycletime ... see start time of ec_dcsync0 ... it makes the same .. :-)

.... // ------------------------------------------ // PLL - ECAT_MASTER - Distributed Clock // ------------------------------------------

    // hasdc => sync local_ts_next to ec_DCtime via cycle_time_offset_ns
    if ( ( ec_slave[0].hasdc == true ) && ( gdata.ECAT_INIT.useDC == true ) ) {

        dc_offset_ns = ( ( ec_DCtime - cycle_time_ns_half )  % cycle_time_ns ) - cycle_time_ns_half;

        if( dc_offset_ns < 0 ) {

            dc_integral_ns++;
        }

        if( dc_offset_ns > 0 ) {

            dc_integral_ns--;
        }
        cycle_time_offset_ns = ( dc_integral_ns - dc_offset_ns ) / gdata.PLC_timerthread.pidivfactor;

    }

....

Now set slaves to OP.

I have check that with scope. All is fine.

PATCH => ethercatconfig.c => int ecx_config_map_group(ecx_contextt context, void pIOmap, uint8 group) => REMARK => ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP) , EC_TIMEOUTRET3); / set safeop status /

.... { segmentsize += diff; } }

        ecx_eeprom2pdi(context, slave); /* set Eeprom control to PDI */

        /* schnick - 27.12.2017 - fixed
          * SAFE_OP disabled after finish ec_config_map(), do it yourself
         * EL5101 can't config DCSYNC0 in SAFE_OP
         */
        **// ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP) , EC_TIMEOUTRET3); /* set safeop status */**

        if (context->slavelist[slave].blockLRW)
        {
           context->grouplist[group].blockLRW++;
        }

....

nakarlsson commented 6 years ago

Perhaps you can use the PREOP->SAFEOP hooks instead of patching ethercatconfig.c?

static int slave_dc_config(uint16 slave) { ... ec_dcsync0(slave, TRUE, period_us * 1000, calc_and_copy); ... return 0; }

...

  if ( ec_config_init(FALSE) > 0 )
  {

... ec_configdc(); ... for(cnt = 1; cnt <= ec_slavecount ; cnt++) { if(ec_slave[cnt].hasdc > 0) { ec_slave[cnt].PO2SOconfig = slave_dc_config; } } ec_config_map(&IOmap); ...

tecodrive commented 6 years ago

I’ve tested. Yes,

sequence ok:

  1. ec_configdc();
  2. ec_dcsync0(…);
  3. ec_config_map(…);
satishdamo commented 6 years ago

Thanks for all valuable guidance. It indeed helped to solve the problem.

satishdamo commented 6 years ago

Dear sir, In Ethercat for multiple slaves configuration, in my case beckhoff el5101-0011 with LnT AC servo drive , what SOEM functions to use and in what sequence so as to synchronize all the slaves with distributed clock mechanism. At present the slaves are only in safeop, not changing to OP. Awaiting for your valuable guidance.

tecodrive commented 6 years ago

@ satishdamo: What are the results with my description above? Have you a realtime-task, which is sync shift_next_cycle_ns = modulo(ec_DCtime , cycletime_ns)?

It's important the jitter of realtime-task is << cycletime, I have not evaluate the max. jitter_ns that's ok for EL5101 incremental encoder. With 250us cycletime , my jitter < 50us on a Linux Ubuntu Desktop. Thats ok for EL5101.

I don't use rt_preempt patch. I use isolcpus an start my realtime task in the isolated cpu. Simple poll to catch next cycle with adjustment of cylcletime via shift_next_cycle_ns.

I map the irq's of network-card to the isolated cpu. Receiving latency of Intel I210 < 20us, Intel I211 <120us, Realtek RT8168 < 20us. When a dedicated NIC-Chip is use on your motherboard, you have latency < 20us. All my tested cpu / chipset integrated NICs have latency > 20us ... 120us.

When you want use NO_HZ, don't use rt_preempt oder low latency kernel. That's use threaded interrupts. You get more than one task on isolated cpu. The task-scheduler will interrupt your realtime-task to check, if another task want to have the cpu (jiffies-time).

With zotac zbox ci547, Ubuntu Server 17.10, no desktop, NO MONITOR, boot from usb micro sd card - better than ssd because ssd driver and integrated graphic card i915 increase cpu cache faults, communication only over ssh, stopped all not important daemons, avoid writing data to sd card, map nic irqs to isolated cpu, run main loop in a not isolated cpu, run realtime plc in the isolated cpu, I get latency = 19us and a jitter of max 0...+3us!!! It's a very low cost solution and super performance and absolut stable.

In future i will access the nic direct with mmio to avoid any interrupts on isolated cpu to reduce latency (not jitter).

Have in mind, every task switch will produce cache faults in the cpu L3. Perhaps the C3558 Atom Server Board with 4x2M L2 with no L3 is a better solution for ultra low latency and stable realtime linux enviroment.

satishdamo commented 6 years ago

@tecodrive: Dear sir, I have followed as you said the sequence of Dc configuration steps. i am using el5101-0011 with oversampling feature. The cycle time set to the PDO task as 1 ms but when read the time difference between the current StartTimeNextLatch and the previous StartTimeNextLatch is showing 1.50 ms. Sometimes the previous x counter values only repeated when reading the current x counter values. So doubt of missing PDO cyclic input from el5101-0011 to master. Sampling factor set as 20, syn0 pulse set as 1 ms same as cycle time and synco pulse set as 50us.
Please let me know what's the cause of this error and how to rectify this.

tecodrive commented 6 years ago

Looks like the el5101 does not in dc mode and/or your plc is not synchronized with ec_DCtime very well.

Did you config the el5101 in pre_op? Does your PLC go error-free into op_mode? You should detached the realtime plc_measurement function from function with using printf. It’s important that you have an stable ec_DCtime.

Check your plc without oversampling of el5101. Compare ec_DCtime with StartNextLatch. First, keep your plc simple. Check step by step simple basics.

satishdamo commented 6 years ago

@tecodrive: Dear sir, indeed there is problem in synchronization. el5101-011 module is connected through beckhoff module ek1818 bus coupler. The SOEM ethercat master ran in beaglebone. Followed the example of SOEM redtest.c and used the same RT EtherCAT thread code for realtime task using xenomai.

coding lines are as follows... Awating for your valuable guidance.

slave_config()

{ //checking state to preop.......

//pdo configurations through sdo ....

ec_configdc();

ec_dcsync01(slave_pos_beck_encoderinterface, TRUE, 100000, 1000000,0); //sampling factor sync1/sync0=10

ec_config_map(&IOmap);

// going to safeop ec_slave[0].state = EC_STATE_SAFE_OP; //write SAFEOP state to all salves ec_writestate(0); ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);

//creating pdo_reatime task() //starting pdo_reatime task()

// moving to op state expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC; //calculate exepected Working counter in SAFEOP state printf("Calculated workcounter %d\n", expectedWKC);

ec_slave[0].state = EC_STATE_OPERATIONAL; / request OP state for all slaves / ec_writestate(0);

ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE); //check

}

main()

{ slave_config();

pause(); //deleting pdo_reatime tas();

}

/ PI calculation to get linux time synced to DC time / void ec_sync(int64 reftime, int64 cycletime , int64 offsettime) { static int64 integral = 0; int64 delta; / set linux sync point 50us later than DC sync, just as example / delta = (reftime - 50000) % cycletime; if(delta> (cycletime / 2)) { delta= delta - cycletime; } if(delta>0){ integral++; } if(delta<0){ integral--; } offsettime = -(delta / 100) - (integral / 20); gl_delta = delta; }

pdo_reatime task() { while(1) { add_timespec(&ts, cycletime + toff); / wait to cycle start / clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &ts, &tleft);

if( ec_slave[0].state == EC_STATE_OPERATIONAL) { wkc = ec_receive_processdata(EC_TIMEOUTRET); if (ec_slave[0].hasdc) {
/ calulate toff to get linux time and DC synced / ec_sync(ec_DCtime, cycletime, &toff); }
ec_send_processdata();
} } }

tecodrive commented 6 years ago

Don’t use ec_dcsync01. Use only ec_dcsync0 for el5101. Cycletime max for el5101 10ms!!! Otherwise el5101 goes not in SAFE_OP or OP.

Don’t shift your realtime sync time to ec_DCtime. Use only shifttime for slave. For test use shifttime = cycletime/2.

delta = (reftime – 50000 / <<= set to zero, do not shift the mastersync / ) % cycletime;

your main loop runs on normal cpu

your timerthread loop run best on dedicated isolated cpu … no other threads! … looks like …

// ================
// ecat_loop
// ================

#define MSEC_PER_SEC                1000
#define USEC_PER_SEC                1000000
#define NSEC_PER_SEC                1000000000

struct timespec         local_ts_next               ,
                        cycle_time_ts               ,
                        poll_time                   ;

int64_t                 cycle_time_us               ,
                        cycle_time_ns               ,
                        cycle_time_ns_half          ,

                        poll_loops              = 0 ,

                        dc_offset_ns            = 0 ,
                        dc_integral_ns          = 0 ,

                        cycle_time_offset_ns    = 0 ;

cycle_time_us          =   250;
cycle_time_ns          =   cycle_time_us * 1000;
cycle_time_ns_half     =   cycle_time_ns / 2;

cycle_time_ts.tv_sec   =   cycle_time_us / USEC_PER_SEC;
cycle_time_ts.tv_nsec  = ( cycle_time_us % USEC_PER_SEC ) * 1000;

clock_gettime( CLOCK_MONOTONIC , &local_ts_next ); // init

while( !shutdown ) {

    // ------------------------------------------
    // local_ts_next
    // ------------------------------------------

    local_ts_next.tv_sec  += cycle_time_ts.tv_sec;
    local_ts_next.tv_nsec += cycle_time_ts.tv_nsec + cycle_time_offset_ns;

    while ( local_ts_next.tv_nsec >= NSEC_PER_SEC ) {
        local_ts_next.tv_nsec -= NSEC_PER_SEC;
        local_ts_next.tv_sec++;
    }

    // ------------------------------------------
    // poll
    // ------------------------------------------
    clock_gettime( CLOCK_MONOTONIC , &poll_time );

    while ( ( local_ts_next.tv_sec >  poll_time.tv_sec ) ||

            ( ( local_ts_next.tv_sec == poll_time.tv_sec ) && ( local_ts_next.tv_nsec > poll_time.tv_nsec ) ) ) {

          // do nothing …
    }

    // ------------------------------------------
    // ec_update
    // ------------------------------------------

    ec_send_processdata();

    wkc = ec_receive_processdata( EC_TIMEOUTRET /* us */ );

    // ------------------------------------------
    // PLL - ECAT_MASTER - Distributed Clock
    // ------------------------------------------
    // hasdc => sync local_ts_next to ec_DCtime via cycle_time_offset_ns

    if  ( ec_slave[0].hasdc == true ) {

        dc_offset_ns = ( ( ec_DCtime - cycle_time_ns_half )  % cycle_time_ns ) - cycle_time_ns_half;

        if( dc_offset_ns < 0 ) {
            dc_integral_ns++;
        }
        if( dc_offset_ns > 0 ) {
            dc_integral_ns--;
        }
        cycle_time_offset_ns = ( dc_integral_ns - dc_offset_ns ) / divfactor; // divfactor for example 2 (cycleitme = 1ms) … 100 (cycletime 250us) 

    }

}

int ECAT_INIT( plc_state_t plc_state ) {

int             slave;

static bool     ec_init_plc_init    = false;
static bool     ec_config_plc_init  = false;

switch ( plc_state ) {

    // =====================================
    // PLC_STATE_INIT
    // =====================================

    case PLC_STATE_INIT:

        // -----------------------------------------------
        // initialise SOEM, bind socket to ifname
        // -----------------------------------------------

        if ( ec_init( gdata.ECAT_INIT.ifname ) == 0 ) {

            printf( "ECAT_INIT => ec_init => root? => No socket connection on %s\n" , gdata.ECAT_INIT.ifname );

            return EXIT_FAILURE;

        }
        ec_init_plc_init = true;

        // -----------------------------------------------
        // find and init slaves
        // -----------------------------------------------

        if ( ec_config_init( FALSE ) == 0 ) {

            printf( "ECAT_INIT => ec_config_init => No slaves found!\n" );

            return EXIT_FAILURE;

        }
        ec_config_plc_init = true;

        // -----------------------------------------------
        // ECAT_check_ecat_device_with_ec_slave
        // -----------------------------------------------

        if ( ECAT_check_ecat_device_with_ec_slave() == EXIT_FAILURE ) {

            printf( "ECAT_INIT => ECAT_check_ecat_device_with_ec_slave => error!\n" );

            return EXIT_FAILURE;

        }

        // -----------------------------------------------
        // check PRE_OP - to configure PDOmapping
        // -----------------------------------------------

        if ( ec_statecheck( 0 , EC_STATE_PRE_OP ,  EC_TIMEOUTSTATE * 4 ) != EC_STATE_PRE_OP ) {

            printf( "ECAT_INIT => ec_statecheck => slaves reached not PRE_OP after ec_config_init! => error\n" );

            return EXIT_FAILURE;

        }

        printf( "ECAT_INIT => ec_statecheck => all slaves has PRE_OP after ec_config_map => success\n" );

        // -----------------------------------------------
        // ECAT_config_ecat_device
        // -----------------------------------------------
        if ( ECAT_config_ecat_device() == EXIT_FAILURE ) {

            printf( "ECAT_INIT => ECAT_config_ecat_device => error!\n" );

           return EXIT_FAILURE;
        }

        // -----------------------------------------------
        // pdo mapping
        //
        // get pdo mapping, ec_config_map set also to SAFE_OP
        //
        // schnick - 27.12.2017
        // fixed" => patched ecx_config_map_group() - ethercatconfig.c
        //
        // set no more to SAFE_OP , because for EL5101, DCSYNC0 cannot set in SAFE_OP, only in PRE_OP
        //
        // -----------------------------------------------

        ec_config_map( &(gdata.ECAT_INIT.IOmap) );

        // -----------------------------------------------
        // expectedWKC
        // -----------------------------------------------

        gdata.PLC_timer_thread.expectedWKC = ( ec_group[0].outputsWKC * 2 ) + ec_group[0].inputsWKC;

        // -----------------------------------------------
        // ECAT_print_slaves
        // -----------------------------------------------
        ECAT_print_slaves();

        // -----------------------------------------------
        // check PRE_OP again after ec_config_map
        //
        // Important - DC can only configured in PRE_OP
        // original ethercatconfig.c set to SAFE_OP after ec_config_map
        // -----------------------------------------------

        if ( ec_statecheck( 0 , EC_STATE_PRE_OP ,  EC_TIMEOUTSTATE * 4 ) != EC_STATE_PRE_OP ) {

             printf( "ECAT_INIT => ec_statecheck => slaves not in PRE_OP - Mode - Cannot configure DC with SYNC0 ! => error\n" );

             return EXIT_FAILURE;

        }

        printf( "ECAT_INIT => ec_statecheck => all slaves has PRE_OP after ec_config_map => success\n" );

        // -----------------------------------------------
        // ECAT_check_iobytes
        // -----------------------------------------------
        if ( ECAT_check_iobytes() == EXIT_FAILURE ) {

            printf( "ECAT_INIT => ECAT_check_iobytes => error!\n" );

            return EXIT_FAILURE;
        }

        // -----------------------------------------------
        // ECAT_config_pdovars_to_iomap
        // -----------------------------------------------
        if ( ECAT_config_pdovars_to_iomap() == EXIT_FAILURE ) {
            printf( "ECAT_INIT => ECAT_config_pdovars_to_iomap => error!\n" );
            return EXIT_FAILURE;
        }

        // -----------------------------------------------
        // ECAT_config_watchdog
        // -----------------------------------------------
        if ( ECAT_config_watchdog() == EXIT_FAILURE ) {
            printf( "ECAT_INIT => ECAT_config_watchdog => error!\n" );
            return EXIT_FAILURE;
        }

        // -----------------------------------------------
        // ECAT_config_dc
        // -----------------------------------------------

        if ( gdata.ECAT_INIT.useDC == true ) {

             if ( ECAT_config_dc( PLC_STATE_INIT ) == EXIT_FAILURE ) {

                printf( "ECAT_INIT => ECAT_config_dc => error!\n" );

                return EXIT_FAILURE;

            }

        }

        // -----------------------------------------------
        // request SAFE_OP
        // -----------------------------------------------
        ec_slave[ 0 ].state = EC_STATE_SAFE_OP;

        ec_writestate( 0 );

        if ( ec_statecheck( 0 , EC_STATE_SAFE_OP ,  EC_TIMEOUTSTATE * 4 ) != EC_STATE_SAFE_OP ) {

            printf( "ECAT_INIT => ec_statecheck => slaves reached not SAFE_OP!\n" );

            return EXIT_FAILURE;

        }

        printf( "All slaves reached SAFE_OP\n" );

        // -----------------------------------------------
        //
        // PLC_timer_thread.ecat_realtime_start
        //
        // -----------------------------------------------
        // start only in SAFE_OP and than wait a while, before go to OP

        // ethercat don't like pdo-Transfer in PRE_OP !

        gdata.PLC_timer_thread.ecat_realtime_start = true;

        // -----------------------------------------------
        // wait PLLs from slaves & master are synchronized
        // -----------------------------------------------
        usleep( gdata.ECAT_INIT.delay_request_OP_ms * 1000  );

        // -----------------------------------------------
        // request OP
        // -----------------------------------------------
        ec_slave[ 0 ].state = EC_STATE_OPERATIONAL;

        ec_writestate( 0 );

         if ( ec_statecheck( 0 , EC_STATE_OPERATIONAL ,  EC_TIMEOUTSTATE * 4 ) != EC_STATE_OPERATIONAL ) {
            printf( "ECAT_INIT => ec_statecheck => slaves reached not OP!\n" );

            return EXIT_FAILURE;

        }

        printf( "All slaves reached OP\n" );

        // -----------------------------------------------
        //  PLC_main.run_main
        // -----------------------------------------------
        gdata.PLC_timer_thread.ecat_realtime_start = true;

        // -----------------------------------------------
        // print error list
        // -----------------------------------------------
        while( EcatError ) printf( "%s" , ec_elist2string() );

        break;

    // =====================================
    // PLC_STATE_SHUTDOWN
    // =====================================
    case PLC_STATE_SHUTDOWN:

        // -----------------------------------------------
        // ECAT_print_states
        // -----------------------------------------------
        if ( ec_config_plc_init == true ) {

            ECAT_print_states_error();

        }

        // -----------------------------------------------
        // ECAT_config_dc
        // -----------------------------------------------
        if ( gdata.ECAT_INIT.useDC == true ) {

            ECAT_config_dc( PLC_STATE_SHUTDOWN );

        } else {

            printf( "ECAT_INIT => ECAT_config_dc => is not touched\n" );

        }

       // -----------------------------------------------
       // request INIT state for all slaves
       // -----------------------------------------------
       if ( ec_config_plc_init == true ) {

            ec_slave[0].state = EC_STATE_INIT;

            ec_writestate( 0 );

        } else {

            printf( "ECAT_INIT => ec_config => is not touched\n" );

        }

        // -----------------------------------------------
        // close socket
        // -----------------------------------------------
        if ( ec_init_plc_init == true ) {

            ec_close();

        } else {

            printf( "ECAT_INIT => ec_init => is not touched\n" );

        }
        break;

}
return EXIT_SUCCESS;

}

satishdamo commented 6 years ago

Dear sir, I have followed the changes you have shown in the code .

I am using Beckhoff module el5101-011 which requires both sync0 and sync1 pulse for DC operation. oversampling factor = sync1/syn0. for example if cycle time is 1 ms, then sync1 = 1ms and set sync0 = 100 us then oversampling factor = 10; i.e., 10 counter values read in every cycle time. But the problem is that starchtimenextlatch difference value between two cycles is to show cycletime value = 1ms, but now it is showing as 1100000.

Please let me know what's the cause of this error and how to rectify this.

satishdamo commented 6 years ago

@tecodrive : Dear sir, in your above code, please let me know where the variables local_ts_next.tv_sec and cycle_time_offset_ns are used ?. Whether it should be used in user defined function in redtest example, i.e ec_sync(ec_DCtime, cycletime, &toff); Awaiting for your valuable guidance.

satishdamo commented 6 years ago

@tecodrive : Inaddition sir, what is local_ts_next.tv_sec variable in relation to redtest sample code.

tecodrive commented 6 years ago

I've update the snippet.

nakarlsson commented 6 years ago

Seems to be fixed!

WangKaimeng commented 5 years ago

calc_and_copy

hello nakarlsson!

I don't know how to choose CyclTime and CyclShift value in function ec_dcsync0(). Thank you in advance!