simple_test.c
Go to the documentation of this file.
00001 
00012 #include <stdio.h>
00013 #include <string.h>
00014 #include <sys/time.h>
00015 #include <unistd.h>
00016 #include <pthread.h>
00017 
00018 #include "ethercat_soem/ethercattype.h"
00019 #include "ethercat_soem/nicdrv.h"
00020 #include "ethercat_soem/ethercatbase.h"
00021 #include "ethercat_soem/ethercatmain.h"
00022 #include "ethercat_soem/ethercatdc.h"
00023 #include "ethercat_soem/ethercatcoe.h"
00024 #include "ethercat_soem/ethercatfoe.h"
00025 #include "ethercat_soem/ethercatconfig.h"
00026 #include "ethercat_soem/ethercatprint.h"
00027 
00028 #define EC_TIMEOUTMON 500
00029 
00030 char IOmap[4096];
00031 pthread_t thread1;
00032 int expectedWKC;
00033 boolean needlf;
00034 volatile int wkc;
00035 boolean inOP;
00036 uint8 currentgroup = 0;
00037 
00038 void simpletest(char *ifname)
00039 {
00040     int i, j, oloop, iloop, wkc_count, chk;
00041     needlf = FALSE;
00042     inOP = FALSE;
00043 
00044    printf("Starting simple test\n");
00045    
00046    /* initialise SOEM, bind socket to ifname */
00047    if (ec_init(ifname))
00048    {   
00049       printf("ec_init on %s succeeded.\n",ifname);
00050       /* find and auto-config slaves */
00051 
00052 
00053        if ( ec_config_init(FALSE) > 0 )
00054       {
00055          printf("%d slaves found and configured.\n",ec_slavecount);
00056 
00057          ec_config_map(&IOmap);
00058 
00059          ec_configdc();
00060 
00061          printf("Slaves mapped, state to SAFE_OP.\n");
00062          /* wait for all slaves to reach SAFE_OP state */
00063          ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE * 4);
00064 
00065          oloop = ec_slave[0].Obytes;
00066          if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
00067          if (oloop > 8) oloop = 8;
00068          iloop = ec_slave[0].Ibytes;
00069          if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1;
00070          if (iloop > 8) iloop = 8;
00071 
00072          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]);
00073 
00074          printf("Request operational state for all slaves\n");
00075          expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
00076          printf("Calculated workcounter %d\n", expectedWKC);
00077          ec_slave[0].state = EC_STATE_OPERATIONAL;
00078          /* send one valid process data to make outputs in slaves happy*/
00079          ec_send_processdata();
00080          ec_receive_processdata(EC_TIMEOUTRET);
00081          /* request OP state for all slaves */
00082          ec_writestate(0);
00083          chk = 40;
00084          /* wait for all slaves to reach OP state */
00085          do
00086          {
00087             ec_send_processdata();
00088             ec_receive_processdata(EC_TIMEOUTRET);
00089             ec_statecheck(0, EC_STATE_OPERATIONAL, 50000);
00090          }
00091          while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));
00092          if (ec_slave[0].state == EC_STATE_OPERATIONAL )
00093          {
00094             printf("Operational state reached for all slaves.\n");
00095             wkc_count = 0;
00096             inOP = TRUE;
00097                 /* cyclic loop */
00098             for(i = 1; i <= 10000; i++)
00099             {
00100                ec_send_processdata();
00101                wkc = ec_receive_processdata(EC_TIMEOUTRET);
00102 
00103                     if(wkc >= expectedWKC)
00104                     {
00105                         printf("Processdata cycle %4d, WKC %d , O:", i, wkc);
00106 
00107                         for(j = 0 ; j < oloop; j++)
00108                         {
00109                             printf(" %2.2x", *(ec_slave[0].outputs + j));
00110                         }
00111 
00112                         printf(" I:");                  
00113                         for(j = 0 ; j < iloop; j++)
00114                         {
00115                             printf(" %2.2x", *(ec_slave[0].inputs + j));
00116                         }   
00117                         printf(" T:%lld\r",ec_DCtime);
00118                         needlf = TRUE;
00119                     }
00120                     usleep(5000);
00121                     
00122                 }
00123                 inOP = FALSE;
00124             }
00125             else
00126             {
00127                 printf("Not all slaves reached operational state.\n");
00128                 ec_readstate();
00129                 for(i = 1; i<=ec_slavecount ; i++)
00130                 {
00131                     if(ec_slave[i].state != EC_STATE_OPERATIONAL)
00132                     {
00133                         printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n",
00134                             i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
00135                     }
00136                 }
00137             }           
00138             printf("\nRequest init state for all slaves\n");
00139             ec_slave[0].state = EC_STATE_INIT;
00140             /* request INIT state for all slaves */
00141             ec_writestate(0);
00142         }
00143         else
00144         {
00145             printf("No slaves found!\n");
00146         }
00147         printf("End simple test, close socket\n");
00148         /* stop SOEM, close socket */
00149         ec_close();
00150     }
00151     else
00152     {
00153         printf("No socket connection on %s\nExcecute as root\n",ifname);
00154     }   
00155 }   
00156 
00157 void ecatcheck( void *ptr )
00158 {
00159     int slave;
00160 
00161     while(1)
00162     {
00163         if( inOP && ((wkc < expectedWKC) || ec_group[currentgroup].docheckstate))
00164         {
00165             if (needlf)
00166             {
00167                needlf = FALSE;
00168                printf("\n");
00169             }
00170             /* one ore more slaves are not responding */
00171             ec_group[currentgroup].docheckstate = FALSE;
00172             ec_readstate();
00173             for (slave = 1; slave <= ec_slavecount; slave++)
00174             {
00175                if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
00176                {
00177                   ec_group[currentgroup].docheckstate = TRUE;
00178                   if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
00179                   {
00180                      printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
00181                      ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
00182                      ec_writestate(slave);
00183                   }
00184                   else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
00185                   {
00186                      printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
00187                      ec_slave[slave].state = EC_STATE_OPERATIONAL;
00188                      ec_writestate(slave);                              
00189                   }
00190                   else if(ec_slave[slave].state > 0)
00191                   {
00192                      if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
00193                      {
00194                         ec_slave[slave].islost = FALSE;
00195                         printf("MESSAGE : slave %d reconfigured\n",slave);                           
00196                      }
00197                   } 
00198                   else if(!ec_slave[slave].islost)
00199                   {
00200                      /* re-check state */
00201                      ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
00202                      if (!ec_slave[slave].state)
00203                      {
00204                         ec_slave[slave].islost = TRUE;
00205                         printf("ERROR : slave %d lost\n",slave);                           
00206                      }
00207                   }
00208                }
00209                if (ec_slave[slave].islost)
00210                {
00211                   if(!ec_slave[slave].state)
00212                   {
00213                      if (ec_recover_slave(slave, EC_TIMEOUTMON))
00214                      {
00215                         ec_slave[slave].islost = FALSE;
00216                         printf("MESSAGE : slave %d recovered\n",slave);                           
00217                      }
00218                   }
00219                   else
00220                   {
00221                      ec_slave[slave].islost = FALSE;
00222                      printf("MESSAGE : slave %d found\n",slave);                           
00223                   }
00224                }
00225             }
00226             if(!ec_group[currentgroup].docheckstate)
00227                printf("OK : all slaves resumed OPERATIONAL.\n");
00228         }
00229         usleep(10000);
00230     }   
00231 }   
00232 
00233 int main(int argc, char *argv[])
00234 {
00235     int iret1;
00236    printf("SOEM (Simple Open EtherCAT Master)\nSimple test\n");
00237 
00238    if (argc > 1)
00239    {      
00240       /* create thread to handle slave error handling in OP */
00241       iret1 = pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);   
00242       /* start cyclic part */
00243       simpletest(argv[1]);
00244    }
00245    else
00246    {
00247       printf("Usage: simple_test ifname1\nifname = eth0 for example\n");
00248    }   
00249    
00250    printf("End program\n");
00251    return (0);
00252 }


ethercat_soem
Author(s): Arthur Ketels, M.J.G. van de Molengraft
autogenerated on Wed Aug 26 2015 11:32:40