This thread has been locked.

If you have a related question, please click the "Ask a related question" button in the top right corner. The newly created question will be automatically linked to this question.

Cannot configure Distributed Clocks SYNC0 on AM3359 with SOEM

Other Parts Discussed in Thread: AM3359, SYSBIOS

I'm unable to configure the AM3359 ICE v2.1 board to synchronize using Distributed Clocks using the Simple Open EtherCAT Master (SOEM) library. 

When I try to configure Distributed Clocks and push the EtherCAT slave(s) into Operational Mode, the slave device(s) eventually transitions into Safe-Op+Error (state = 0x14) and reports AL StatusCode = 0x2D (No sync error), so it looks like the application is being configured to use the SYNC0 HW pin as a trigger, but the SYNC0 line never pulses.

Note that D.C. SYNC0 does seem to work correctly with TwinCAT v2.11, but looking through the Wireshark logs between the TwinCAT and SOEM configuration it appears as if most of the Synchronization configuration is the same... I'm told that SOEM can successfully configure other EtherCAT slave devices (non-AM3359) to use Distributed Clocks.

I'm using the following environment:

  • SOEM v1.3.1 with modified "simple_test" application (see attached file)
  • GNU v4.8.4 (Linaro)
  • SYS/BIOS 6.42.3.35- XDCtools 3.31.2.38_core
  • sysbios_ind_sdk_2.1.1.2
  • TI EtherCAT sample application (from sysbios_ind_sdk_2.1.1.2\sdk\examples\ethercat_slave)

  1. Is there any special configuration required to get the SYNC0 pin on AM3359 to pulse? 
  2. EtherCAT register 0x0141 (ESC Configuration) looks to always be read as 0x00, but according to the EtherCAT Register Description document it should be 0x04 to enable Distributed Clocks SYNC Out Unit... however, TwinCAT seems to trigger Distributed Clocks just fine despite this setting.  
    Does register 0x0141 have any affect with the AM3359?
  3. EtherCAT register 0x0151 (Sync/Latch PDI Configuration) value reads 0x88 which according to the EtherCAT Register Description document means that the HW pin will be configured as "LATCH0 Input" (as opposed to "SYNC0 Output"), yet once again TwinCAT seems to trigger D.C. just fine.
    Does register 0x0151 have any affect with the AM3359?

Are there any other possible steps I could be missing in configuring the EtherCAT Slave to use Distributed Clocks SYNC0?

SOEM_simple_test.c
/** \file
 * \brief Example code for Simple Open EtherCAT master
 *
 * Usage : simple_test [ifname1]
 * ifname is NIC interface, f.e. eth0
 *
 * This is a minimal test.
 *
 * (c)Arthur Ketels 2010 - 2011
 */

#include <stdio.h>
#include <string.h>
#include <sys/time.h>
#include <unistd.h>
#include <pthread.h>

#include "ethercattype.h"
#include "nicdrv.h"
#include "ethercatbase.h"
#include "ethercatmain.h"
#include "ethercatdc.h"
#include "ethercatcoe.h"
#include "ethercatfoe.h"
#include "ethercatconfig.h"
#include "ethercatprint.h"

#define EC_TIMEOUTMON 500

char IOmap[4096];
OSAL_THREAD_HANDLE thread1;
int expectedWKC;
boolean needlf;
volatile int wkc;
boolean inOP;
uint8 currentgroup = 0;

void simpletest(char *ifname)
{
    int i, j, oloop, iloop, chk;
    needlf = FALSE;
    inOP = FALSE;

   printf("Starting simple test\n");
   
   /* initialise SOEM, bind socket to ifname */
   if (ec_init(ifname))
   {   
      printf("ec_init on %s succeeded.\n",ifname);
      
      /* find and auto-config slaves */
       if ( ec_config_init(FALSE) > 0 )
       {
         printf("%d slaves found and configured.\n",ec_slavecount);
        
         // TI defect SDOCM00105048, cannot use LRW commands
         ec_slave[1].blockLRW = 1;
         ecx_context.grouplist[0].blockLRW = 1;
         
         // Configure Distributed Clocks
         ec_configdc();
         ec_dcsync0(1, TRUE, 1000000U, 0);
         
         // Configure IOMAP
         ec_config_map(&IOmap);

         printf("Slaves mapped, state to SAFE_OP.\n");
         /* wait for all slaves to reach SAFE_OP state */
         ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE * 4);

         oloop = ec_slave[0].Obytes;
         if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
         if (oloop > 8) oloop = 8;
         iloop = ec_slave[0].Ibytes;
         if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1;
         if (iloop > 8) iloop = 8;

         printf("segments : %d : %d %d %d %d\n",ec_group[0].nsegments ,ec_group[0].IOsegment[0],ec_group[0].IOsegment[1],ec_group[0].IOsegment[2],ec_group[0].IOsegment[3]);

         printf("Request operational state for all slaves\n");
         expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
         printf("Calculated workcounter %d\n", expectedWKC);
         ec_slave[0].state = EC_STATE_OPERATIONAL;
         
         /* send one valid process data to make outputs in slaves happy*/
         ec_send_processdata();
         ec_receive_processdata(EC_TIMEOUTRET);
         
         /* request OP state for all slaves */
         ec_writestate(0);
         chk = 40;
         
         /* wait for all slaves to reach OP state */
         do
         {
            ec_send_processdata();
            ec_receive_processdata(EC_TIMEOUTRET);
            ec_statecheck(0, EC_STATE_OPERATIONAL, 1000000);
         }
         while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));
         
         if (ec_slave[0].state == EC_STATE_OPERATIONAL )
         {
            printf("Operational state reached for all slaves.\n");
            inOP = TRUE;
            
            /* cyclic loop */
            for(i = 1; i <= 1000; i++)
            {
               ec_send_processdata();
               wkc = ec_receive_processdata(EC_TIMEOUTRET);

                    if(wkc >= expectedWKC)
                    {
                        printf("Processdata cycle %4d, WKC %d , O:", i, wkc);

                        for(j = 0 ; j < oloop; j++)
                        {
                            printf(" %2.2x", *(ec_slave[0].outputs + j));
                        }

                        printf(" I:");                  
                        for(j = 0 ; j < iloop; j++)
                        {
                            printf(" %2.2x", *(ec_slave[0].inputs + j));
                        }   
                        printf(" T:%lld\r",ec_DCtime);
                        needlf = TRUE;
                    }
                    usleep(5000);
                    
                }
                inOP = FALSE;
            }
        else
        {
            printf("Not all slaves reached operational state.\n");
            ec_readstate();
            for(i = 1; i<=ec_slavecount ; i++)
            {
                if(ec_slave[i].state != EC_STATE_OPERATIONAL)
                {
                    printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n",
                        i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
                }
            }
        } 
        printf("\nRequest init state for all slaves\n");
        ec_slave[0].state = EC_STATE_INIT;
        /* request INIT state for all slaves */
        ec_writestate(0);
    }
    else
    {
        printf("No slaves found!\n");
    }
    printf("End simple test, close socket\n");
    /* stop SOEM, close socket */
    ec_close();
}
else
{
    printf("No socket connection on %s\nExcecute as root\n",ifname);
}   
}   

OSAL_THREAD_FUNC ecatcheck( void *ptr )
{
    int slave;

    while(1)
    {
        if( inOP && ((wkc < expectedWKC) || ec_group[currentgroup].docheckstate))
        {
            if (needlf)
            {
               needlf = FALSE;
               printf("\n");
            }
            /* one ore more slaves are not responding */
            ec_group[currentgroup].docheckstate = FALSE;
            ec_readstate();
            for (slave = 1; slave <= ec_slavecount; slave++)
            {
               if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
               {
                  ec_group[currentgroup].docheckstate = TRUE;
                  if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
                  {
                     printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
                     ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
                     ec_writestate(slave);
                  }
                  else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
                  {
                     printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
                     ec_slave[slave].state = EC_STATE_OPERATIONAL;
                     ec_writestate(slave);                              
                  }
                  else if(ec_slave[slave].state > 0)
                  {
                     if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
                     {
                        ec_slave[slave].islost = FALSE;
                        printf("MESSAGE : slave %d reconfigured\n",slave);                           
                     }
                  } 
                  else if(!ec_slave[slave].islost)
                  {
                     /* re-check state */
                     ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
                     if (!ec_slave[slave].state)
                     {
                        ec_slave[slave].islost = TRUE;
                        printf("ERROR : slave %d lost\n",slave);                           
                     }
                  }
               }
               if (ec_slave[slave].islost)
               {
                  if(!ec_slave[slave].state)
                  {
                     if (ec_recover_slave(slave, EC_TIMEOUTMON))
                     {
                        ec_slave[slave].islost = FALSE;
                        printf("MESSAGE : slave %d recovered\n",slave);                           
                     }
                  }
                  else
                  {
                     ec_slave[slave].islost = FALSE;
                     printf("MESSAGE : slave %d found\n",slave);                           
                  }
               }
            }
            if(!ec_group[currentgroup].docheckstate)
               printf("OK : all slaves resumed OPERATIONAL.\n");
        }
        usleep(10000);
    }   
}   

int main(int argc, char *argv[])
{
   printf("SOEM (Simple Open EtherCAT Master)\nSimple test\n");

   if (argc > 1)
   {      
      /* create thread to handle slave error handling in OP */
//      pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);   
      osal_thread_create(&thread1, 128000, &ecatcheck, (void*) &ctime);
      /* start cyclic part */
      simpletest(argv[1]);
   }
   else
   {
      printf("Usage: simple_test ifname1\nifname = eth0 for example\n");
   }   
   
   printf("End program\n");
   return (0);
}

  • Hi,

    I will ask the Industrial team to comment.
  • Hi Jeff

    I apologize for the delay. There is a issue in that TI  EtherCAT does not support LRW in the same manner as SOEM. In the release notes in {Installed_Directory}\sysbios_ind_sdk_2.1.1.2\sdk\docs there is an issue and workaround provided for this. This listed as issue SDOCM00105048. There is also an e2e thread on this at  https://e2e.ti.com/support/arm/sitara_arm/f/791/t/435658

    In the 2.1.1.2 release, there is a firmware bug with masters using DC slave mode. There is a work around that is discussed in https://e2e.ti.com/support/arm/sitara_arm/f/791/p/482637/1761891#1761891 which is to set the system time delay to 1 ns for first DC slave (ref).

    This bug will be fixed in upcoming the releases 1.1.1.1 and 2.1.2.1.

    David

  • Thanks for getting back to me David.

    Unfortunately I'm still unable to enable D.C. with SOEM using your suggested work-around (writing a value of '1' to register 0x928).  I've modified the SOEM simple_test.c to do this: here is the setup:

       printf("Starting simple test\n");
       
       /* initialise SOEM, bind socket to ifname */
       if (ec_init(ifname))
       {   
          printf("ec_init on %s succeeded.\n",ifname);
    	 
          /* find and auto-config slaves */
           if ( ec_config_init(FALSE) > 0 )
           {
             printf("%d slaves found and configured.\n",ec_slavecount);
    		
    		 // TI defect SDOCM00105048, cannot use LRW commands
    		 ec_slave[1].blockLRW = 1;
    		 ecx_context.grouplist[0].blockLRW = 1;
    		 
    		 // Configure Distributed Clocks
    		 ec_configdc();
    		 ec_dcsync0(1, TRUE, 1000000U, 0);
    		 
    		 // Configure IOMAP
             ec_config_map(&IOmap);
    
    		 // TI suggested work-around; 
    		 // set the system time delay to 1 ns for first DC slave (ref).
             uint32 sysTimeDelay = 1;
    		 ec_FPWR(0x1001, 0x928, sizeof(sysTimeDelay), &sysTimeDelay, EC_TIMEOUTRET);
    
             printf("Slaves mapped, state to SAFE_OP.\n");
             /* wait for all slaves to reach SAFE_OP state */
             ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE * 4);

    I've attached the full test application to this post.

    The observed behaviour is the same -- EcSlave will not transition to OP mode, and eventually throws a "no sync" error (AL status code 0x2d).

    Our code already blocks LRW, as the AM3359 slave boards do not respond to PDOs without that work-around.

    simple_test.c
    /** \file
     * \brief Example code for Simple Open EtherCAT master
     *
     * Usage : simple_test [ifname1]
     * ifname is NIC interface, f.e. eth0
     *
     * This is a minimal test.
     *
     * (c)Arthur Ketels 2010 - 2011
     */
    
    #include <stdio.h>
    #include <string.h>
    #include <sys/time.h>
    #include <unistd.h>
    #include <pthread.h>
    
    #include "ethercattype.h"
    #include "nicdrv.h"
    #include "ethercatbase.h"
    #include "ethercatmain.h"
    #include "ethercatdc.h"
    #include "ethercatcoe.h"
    #include "ethercatfoe.h"
    #include "ethercatconfig.h"
    #include "ethercatprint.h"
    
    #define EC_TIMEOUTMON 500
    
    char IOmap[4096];
    OSAL_THREAD_HANDLE thread1;
    int expectedWKC;
    boolean needlf;
    volatile int wkc;
    boolean inOP;
    uint8 currentgroup = 0;
    
    void simpletest(char *ifname)
    {
        int i, j, oloop, iloop, chk;
        needlf = FALSE;
        inOP = FALSE;
    
       printf("Starting simple test\n");
       
       /* initialise SOEM, bind socket to ifname */
       if (ec_init(ifname))
       {   
          printf("ec_init on %s succeeded.\n",ifname);
    	 
          /* find and auto-config slaves */
           if ( ec_config_init(FALSE) > 0 )
           {
             printf("%d slaves found and configured.\n",ec_slavecount);
    		
    		 // TI defect SDOCM00105048, cannot use LRW commands
    		 ec_slave[1].blockLRW = 1;
    		 ecx_context.grouplist[0].blockLRW = 1;
    		 
    		 // Configure Distributed Clocks
    		 ec_configdc();
    		 ec_dcsync0(1, TRUE, 1000000U, 0);
    		 
    		 // Configure IOMAP
             ec_config_map(&IOmap);
    
    		 // TI suggested work-around; 
    		 // set the system time delay to 1 ns for first DC slave (ref).
             uint32 sysTimeDelay = 1;
    		 ec_FPWR(0x1001, 0x928, sizeof(sysTimeDelay), &sysTimeDelay, EC_TIMEOUTRET);
    
             printf("Slaves mapped, state to SAFE_OP.\n");
             /* wait for all slaves to reach SAFE_OP state */
             ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE * 4);
    
             oloop = ec_slave[0].Obytes;
             if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
             if (oloop > 8) oloop = 8;
             iloop = ec_slave[0].Ibytes;
             if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1;
             if (iloop > 8) iloop = 8;
    
             printf("segments : %d : %d %d %d %d\n",ec_group[0].nsegments ,ec_group[0].IOsegment[0],ec_group[0].IOsegment[1],ec_group[0].IOsegment[2],ec_group[0].IOsegment[3]);
    
             printf("Request operational state for all slaves\n");
             expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
             printf("Calculated workcounter %d\n", expectedWKC);
             ec_slave[0].state = EC_STATE_OPERATIONAL;
             
             /* send one valid process data to make outputs in slaves happy*/
             ec_send_processdata();
             ec_receive_processdata(EC_TIMEOUTRET);
             
             /* request OP state for all slaves */
             ec_writestate(0);
             chk = 40;
             
             /* wait for all slaves to reach OP state */
             do
             {
                ec_send_processdata();
                ec_receive_processdata(EC_TIMEOUTRET);
                ec_statecheck(0, EC_STATE_OPERATIONAL, 1000000);
             }
             while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));
             
             if (ec_slave[0].state == EC_STATE_OPERATIONAL )
             {
                printf("Operational state reached for all slaves.\n");
                inOP = TRUE;
                
                /* cyclic loop */
                for(i = 1; i <= 1000; i++)
                {
                   ec_send_processdata();
                   wkc = ec_receive_processdata(EC_TIMEOUTRET);
    
                        if(wkc >= expectedWKC)
                        {
                            printf("Processdata cycle %4d, WKC %d , O:", i, wkc);
    
                            for(j = 0 ; j < oloop; j++)
                            {
                                printf(" %2.2x", *(ec_slave[0].outputs + j));
                            }
    
                            printf(" I:");                  
                            for(j = 0 ; j < iloop; j++)
                            {
                                printf(" %2.2x", *(ec_slave[0].inputs + j));
                            }   
                            printf(" T:%lld\r",ec_DCtime);
                            needlf = TRUE;
                        }
                        usleep(5000);
                        
                    }
                    inOP = FALSE;
                }
    		else
    		{
    			printf("Not all slaves reached operational state.\n");
    			ec_readstate();
    			for(i = 1; i<=ec_slavecount ; i++)
    			{
    				if(ec_slave[i].state != EC_STATE_OPERATIONAL)
    				{
    					printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n",
    						i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
    				}
    			}
    		} 
    		printf("\nRequest init state for all slaves\n");
    		ec_slave[0].state = EC_STATE_INIT;
    		/* request INIT state for all slaves */
    		ec_writestate(0);
    	}
    	else
    	{
    		printf("No slaves found!\n");
    	}
    	printf("End simple test, close socket\n");
    	/* stop SOEM, close socket */
    	ec_close();
    }
    else
    {
    	printf("No socket connection on %s\nExcecute as root\n",ifname);
    }   
    }   
    
    OSAL_THREAD_FUNC ecatcheck( void *ptr )
    {
        int slave;
    
        while(1)
        {
            if( inOP && ((wkc < expectedWKC) || ec_group[currentgroup].docheckstate))
            {
                if (needlf)
                {
                   needlf = FALSE;
                   printf("\n");
                }
                /* one ore more slaves are not responding */
                ec_group[currentgroup].docheckstate = FALSE;
                ec_readstate();
                for (slave = 1; slave <= ec_slavecount; slave++)
                {
                   if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
                   {
                      ec_group[currentgroup].docheckstate = TRUE;
                      if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
                      {
                         printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
                         ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
                         ec_writestate(slave);
                      }
                      else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
                      {
                         printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
                         ec_slave[slave].state = EC_STATE_OPERATIONAL;
                         ec_writestate(slave);                              
                      }
                      else if(ec_slave[slave].state > 0)
                      {
                         if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
                         {
                            ec_slave[slave].islost = FALSE;
                            printf("MESSAGE : slave %d reconfigured\n",slave);                           
                         }
                      } 
                      else if(!ec_slave[slave].islost)
                      {
                         /* re-check state */
                         ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
                         if (!ec_slave[slave].state)
                         {
                            ec_slave[slave].islost = TRUE;
                            printf("ERROR : slave %d lost\n",slave);                           
                         }
                      }
                   }
                   if (ec_slave[slave].islost)
                   {
                      if(!ec_slave[slave].state)
                      {
                         if (ec_recover_slave(slave, EC_TIMEOUTMON))
                         {
                            ec_slave[slave].islost = FALSE;
                            printf("MESSAGE : slave %d recovered\n",slave);                           
                         }
                      }
                      else
                      {
                         ec_slave[slave].islost = FALSE;
                         printf("MESSAGE : slave %d found\n",slave);                           
                      }
                   }
                }
                if(!ec_group[currentgroup].docheckstate)
                   printf("OK : all slaves resumed OPERATIONAL.\n");
            }
            usleep(10000);
        }   
    }   
    
    int main(int argc, char *argv[])
    {
       printf("SOEM (Simple Open EtherCAT Master)\nSimple test\n");
    
       if (argc > 1)
       {      
          /* create thread to handle slave error handling in OP */
    //      pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);   
          osal_thread_create(&thread1, 128000, &ecatcheck, (void*) &ctime);
          /* start cyclic part */
          simpletest(argv[1]);
       }
       else
       {
          printf("Usage: simple_test ifname1\nifname = eth0 for example\n");
       }   
       
       printf("End program\n");
       return (0);
    }
    

  • I'm still unable to get D.C. working properly with SOEM Master, however there's a new observation:

    During Pre-Op, I write register 0x0980 to '0x300' (indicating to use D.C.) and set the frame time to 1ms (write register 0x9A0 to '1000000').  The EcSlave is then pushed into Safe-Op, and I can see the D.C. SYNC0 line begin to pulse with a period of 1ms, and the embedded software reacting to the SYNC0 event (inside function 'Void Sync0task(UArg arg1, UArg arg2)' in tiescutils.c)

    However, when I try to push the EcSlave into OP mode, the transition fails with the NO SYNC error (0x2d) as before, yet I clearly see the SYNC0 pin pulsing.

    Have any other EtherCAT issues been discovered with D.C. in SYSBIOS Industrial SDK 2.1.1.2 ?

  • Is this issue being investigated? This is a showstopper for our product development.
  • Jeffrey

     

    If we disable  watchdog timer SM WD *(0x4a32e214) == 0, the interface goes to OP state.  When using  a Beckhoff  we see 3 LWR (0, 170us, 340us) to reach to OP state followed by LWR every 5 ms ( note that watchdog time out is 100ms by default).  When using TI, we see only 2 LWR (0, 230us) followed by LWR every 1s. It is the 1 second duration at is forcing the WD timeout.

     We suspect the  SOEM master test code highlighted below. It is necessary to sustain process data write at a rate so that WD does not expire – but in this case ec_satecheck is blocking. Note that for TI ESC, the slave stack is managing the state change so unlike a device without host CPU – AL status (0x130) won’t be updated instantly on write to AL control (0x120)

     

         /* send one valid process data to make outputs in slaves happy*/

             ec_send_processdata();

             ec_receive_processdata(EC_TIMEOUTRET);

     

             /* request OP state for all slaves */

             ec_writestate(0);

             chk = 40;

     

             /* wait for all slaves to reach OP state */

             do

             {

                ec_send_processdata();

                ec_receive_processdata(EC_TIMEOUTRET);

                ec_statecheck(0, EC_STATE_OPERATIONAL, 1000000);    // line to change

             }

             while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));

     

    With following changes the system going consistently to OP state

     

             /* request OP state for all slaves */

             ec_writestate(0);

             chk = 40;

      

             /* wait for all slaves to reach OP state */

             do

             {

                ec_send_processdata();

                ec_receive_processdata(EC_TIMEOUTRET);

                ec_statecheck(0, EC_STATE_OPERATIONAL, 80000);  //80 ms timeout

             }

             while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));

     

     

    David

  • Thanks for getting back to me, David.

    Unfortunately changing the ec_statecheck timeout from 1s to 80ms did not fix the issue. I found that even TwinCAT was unable to get the EtherCAT slave into OP mode with Distributed Clocks.

    However, when I set the IF statement on line 2117 of ecatslv.c to always evaluate True;

    if(sSyncManOutPar.u16SmEventMissedCounter < sErrorSettings.u16SyncErrorCounterLimit)

    I was able to get TwinCAT 2.11 to push the EtherCAT Slave(s) into OP mode with Distributed Clocks SYNC0 pulsing (observed on the SYNC0 pin with an oscilloscope)

    Can you give me more details regarding your statement

    David Zaucha said:
    If we disable  watchdog timer SM WD *(0x4a32e214) == 0, the interface goes to OP state. 

     Does that involve the code change I mentioned above?

    Also, what embedded software did you use to test this? The example program from \sysbios_ind_sdk_2.1.1.2\sdk\examples\ethercat_slave, or an application using the full EtherCAT Slave Stack?

  • Hi Jeffrey,


    I'm the programmer of SOEM. Via your thread on ETG I found this post. A common mistake when implementing DC mode with SOEM is to use the simple example code.


    Most DC slaves expect a stable and syncronised PDO transfer during safe-OP. Only when the LRW or LRD/LWR sequence has "proven" to the slave in question it is in sync with the SYNC0 signal the slave will allow transition to OP.


    So your SOEM application has to:

    - configure the slave

    - map the slave

    - configure distributed clock

    - go to safe-op

    - start pdo data transfer (LRW or LRD/LWR) at the desired DC interval (for example 1ms)

    - check for stable DC clock in all slaves (difference timer)

    - check for stable master clock (digital PLL locked to reference slave)

    - only then request OP

    An example how to do this is in red_test.c in the soem test map.


    Success, Arthur

  • Thank you very much Arthur, your suggestion of sending PDOs during Safe-Op has greatly improved the ability to start the SYNC0 pulses on the EtherCAT Slaves.

    However, I cannot get the EtherCAT slave(s) to start their sync pulses 100% reliably. My particular application will configure/map the slave once upon start-up (getting EtherCAT Slave to SAFE-OP) and only transition slaves to OP mode when we want the application to execute, and when done transition the slaves back to SAFE-OP. I have two further questions for clarification:

    1. In the sequence you mentioned, at what point should I set the DC SYNC Start Time register? (0x990)

    2. You mentioned that the LRD/LWR sequence has to be "proven" to the slave -- is there some register I can check to see if the sequence/configuration is done properly?

  • Hi Jeff,

    Different slaves behave a bit different with regard to SYNC0 and master PDO transfer timing. But in general one can mess around a lot in safe-op. Before starting PDO transfer one should do ec_configdc(); This will measure the timestamps between slave ports and calculate the propagation delays. It also resets the DC registers. Then after transition to safe-op and after positive check for master sync (see above post) one would fire up the SYNC0 of all relevant slaves.
    ec_dcsync0(1, TRUE, 1000000U, 0);
    This will start sync0 at (current slave time modulus CyclTime) + CyclTime + 100ms + CyclShift. In your case CyclTime is 1ms and CyclShift is zero. You will have to wait going into OP mode for at least 101ms. But most slaves will only accept OP when it has processed 3 to 10 SYNC0. So add another 10 to 100ms. The slave has ample time this way to count valid SYNC0 and PDO transfers. It must see one PDO transfer for each SYNC0 and that multiple times in a row. This is the sync "prove" the slave wants. Only then it will go to OP. One issue could apear when the PDO transfer is almost on top of the SYNC0. Then sometimes there will be two PDO's for each SYNC0 or no PDO at a SYNC0 interval. Both will trigger errors in the slave. Use CyclShift to move SYNC0 away from the PDO transfer slot. Remember the master PDO transfers must be synchronised with the SYNC0 on the slaves at all times. That is why you need to have latency guarantees on your master system.
  • Hello Jeffrey.
    I'm trying to make working example of EtherCAT master, like you did before.
    But I have got a problem with sending etherCAT packets via AM3359 ICE v2.1.
    As I realized, SOEM function ecx_outframe_red() should send them but I cannot understand how to do it through AM3359.

    Could you explain how did you connected SOEM sending function with AM3359 ICE v2.1.
    Thanks a lot.

    Best regards,
    Aliaksei Rusakovich
    aliaksei.rusakovich@gmail.com
  • Hi Aliaksei,
    the above case is different to yours. Above uses ICE board as EtherCAT slave. That is an application that is fully support by our IA-SDK software. It is using the Beckhoff slave stack. The master was most likely some PC running SOEM.

    However if you want to run SOEM on AM335x and implement an EtherCAT master you need to a bit more work. There is no released example of this from TI. We have done it for some experimental work and it works. But this didn't reach product level and we don't support it at the current time.
    If you run Linux on ICE (see latest Linuc Processor SDKs) you can port SOEM on top of this. For Ethernet you may use CPSW or PRU-ICSS in that case. Packets are processed using raw socket interfaces. I think SOEM provides examples of Linux port.

    For any further questions I suggest to open a new forum entry. But don't expect full support for SOEM issues as this is open source software not owned or maintained by us.

    Alternatively there are TI Designs available showcasing Acontis EtherCAT master running on Sitara. This is a fully supported commercial solution.

    regards,
  • Hi Frank,
    Thanks for your fast reply and explanation. Sorry for my misunderstanding.
    I'll try to run SOEM on ICE board, but you might have a simple example with sending and receiving raw Ethernet packets through ICE board.
    Thank you.

    Best regards,
    Aliaksei Rusakovich
    aliaksei.rusakovich@gmail.com
  • Sorry, no I do not have a simple example. I know it works from some other customer example but I can't distribute that. Basically in Linux we are using standard sockets API. You can get support for that on our Linux forum in case of issues.

    Regards,