red_test.c
Go to the documentation of this file.
00001 
00013 #include <stdio.h>
00014 #include <stdlib.h>
00015 #include <sys/time.h>
00016 #include <unistd.h>
00017 #include <sched.h>
00018 #include <string.h>
00019 #include <sys/time.h>
00020 #include <time.h>
00021 #include <pthread.h>
00022 #include <math.h>
00023 
00024 #include "ethercat_soem/ethercattype.h"
00025 #include "ethercat_soem/nicdrv.h"
00026 #include "ethercat_soem/ethercatbase.h"
00027 #include "ethercat_soem/ethercatmain.h"
00028 #include "ethercat_soem/ethercatcoe.h"
00029 #include "ethercat_soem/ethercatconfig.h"
00030 #include "ethercat_soem/ethercatdc.h"
00031 #include "ethercat_soem/ethercatprint.h"
00032 
00033 #define NSEC_PER_SEC 1000000000
00034 #define EC_TIMEOUTMON 500
00035 
00036 struct sched_param schedp;
00037 char IOmap[4096];
00038 pthread_t thread1, thread2;
00039 struct timeval tv, t1, t2;
00040 int dorun = 0;
00041 int deltat, tmax = 0;
00042 int64 toff, gl_delta;
00043 int DCdiff;
00044 int os;
00045 uint8 ob;
00046 uint16 ob2;
00047 pthread_cond_t      cond  = PTHREAD_COND_INITIALIZER;
00048 pthread_mutex_t     mutex = PTHREAD_MUTEX_INITIALIZER;
00049 uint8 *digout = 0;
00050 int expectedWKC;
00051 boolean needlf;
00052 volatile int wkc;
00053 boolean inOP;
00054 uint8 currentgroup = 0;
00055 
00056 
00057 void redtest(char *ifname, char *ifname2)
00058 {
00059    int cnt, i, j, oloop, iloop;
00060    
00061    printf("Starting Redundant test\n");
00062    
00063    /* initialise SOEM, bind socket to ifname */
00064    if (ec_init_redundant(ifname, ifname2))
00065    {   
00066       printf("ec_init on %s succeeded.\n",ifname);
00067       /* find and auto-config slaves */
00068       if ( ec_config(FALSE, &IOmap) > 0 )
00069       {
00070          printf("%d slaves found and configured.\n",ec_slavecount);
00071          /* wait for all slaves to reach SAFE_OP state */
00072          ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE);
00073          
00074          /* configure DC options for every DC capable slave found in the list */
00075          ec_configdc();
00076                   
00077          /* read indevidual slave state and store in ec_slave[] */
00078          ec_readstate();
00079          for(cnt = 1; cnt <= ec_slavecount ; cnt++)
00080          {
00081             printf("Slave:%d Name:%s Output size:%3dbits Input size:%3dbits State:%2d delay:%d.%d\n",
00082                   cnt, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits,
00083                   ec_slave[cnt].state, (int)ec_slave[cnt].pdelay, ec_slave[cnt].hasdc);
00084             printf("         Out:%8.8x,%4d In:%8.8x,%4d\n",
00085                   (int)ec_slave[cnt].outputs, ec_slave[cnt].Obytes, (int)ec_slave[cnt].inputs, ec_slave[cnt].Ibytes);
00086             /* check for EL2004 or EL2008 */
00087             if( !digout && ((ec_slave[cnt].eep_id == 0x0af83052) || (ec_slave[cnt].eep_id == 0x07d83052)))
00088             {
00089                digout = ec_slave[cnt].outputs;
00090             }   
00091          }
00092          expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
00093          printf("Calculated workcounter %d\n", expectedWKC);
00094 
00095          printf("Request operational state for all slaves\n");
00096          ec_slave[0].state = EC_STATE_OPERATIONAL;
00097          /* request OP state for all slaves */
00098          ec_writestate(0);
00099          /* activate cyclic process data */
00100          dorun = 1;
00101          /* wait for all slaves to reach OP state */
00102          ec_statecheck(0, EC_STATE_OPERATIONAL,  EC_TIMEOUTSTATE);
00103          oloop = ec_slave[0].Obytes;
00104          if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
00105          if (oloop > 8) oloop = 8;
00106          iloop = ec_slave[0].Ibytes;
00107          if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1;
00108          if (iloop > 8) iloop = 8;
00109          if (ec_slave[0].state == EC_STATE_OPERATIONAL )
00110          {
00111             printf("Operational state reached for all slaves.\n");
00112             inOP = TRUE;
00113             /* acyclic loop 5000 x 20ms = 10s */
00114             for(i = 1; i <= 5000; i++)
00115             {
00116                printf("Processdata cycle %5d , Wck %3d, DCtime %12lld, dt %12lld, O:",
00117                   dorun, wkc , ec_DCtime, gl_delta);
00118                for(j = 0 ; j < oloop; j++)
00119                {
00120                   printf(" %2.2x", *(ec_slave[0].outputs + j));
00121                }
00122                printf(" I:");
00123                for(j = 0 ; j < iloop; j++)
00124                {
00125                   printf(" %2.2x", *(ec_slave[0].inputs + j));
00126                }   
00127                printf("\r");
00128                fflush(stdout);
00129                osal_usleep(20000);
00130             }
00131             dorun = 0;
00132             inOP = FALSE;
00133          }
00134          else
00135          {
00136             printf("Not all slaves reached operational state.\n");
00137              ec_readstate();
00138              for(i = 1; i<=ec_slavecount ; i++)
00139              {
00140                  if(ec_slave[i].state != EC_STATE_OPERATIONAL)
00141                  {
00142                      printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n",
00143                          i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
00144                  }
00145              }
00146          }         
00147          printf("Request safe operational state for all slaves\n");
00148          ec_slave[0].state = EC_STATE_SAFE_OP;
00149          /* request SAFE_OP state for all slaves */
00150          ec_writestate(0);
00151       }
00152       else
00153       {
00154          printf("No slaves found!\n");
00155       }
00156       printf("End redundant test, close socket\n");
00157       /* stop SOEM, close socket */
00158       ec_close();
00159    }
00160    else
00161    {
00162       printf("No socket connection on %s\nExcecute as root\n",ifname);
00163    }   
00164 }   
00165 
00166 /* add ns to timespec */
00167 void add_timespec(struct timespec *ts, int64 addtime)
00168 {
00169    int64 sec, nsec;
00170    
00171    nsec = addtime % NSEC_PER_SEC;
00172    sec = (addtime - nsec) / NSEC_PER_SEC;
00173    ts->tv_sec += sec;
00174    ts->tv_nsec += nsec;
00175    if ( ts->tv_nsec > NSEC_PER_SEC ) 
00176    { 
00177       nsec = ts->tv_nsec % NSEC_PER_SEC;
00178       ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
00179       ts->tv_nsec = nsec;
00180    }   
00181 }   
00182 
00183 /* PI calculation to get linux time synced to DC time */
00184 void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
00185 {
00186    static int64 integral = 0;
00187    int64 delta;
00188    /* set linux sync point 50us later than DC sync, just as example */
00189    delta = (reftime - 50000) % cycletime;
00190    if(delta> (cycletime / 2)) { delta= delta - cycletime; }
00191    if(delta>0){ integral++; }
00192    if(delta<0){ integral--; }
00193    *offsettime = -(delta / 100) - (integral / 20);
00194    gl_delta = delta;
00195 }   
00196 
00197 /* RT EtherCAT thread */
00198 void ecatthread( void *ptr )
00199 {
00200    struct timespec   ts, tleft;
00201    struct timeval    tp;
00202    int rc;
00203    int ht;
00204    int64 cycletime;
00205    
00206    rc = pthread_mutex_lock(&mutex);
00207    rc = clock_gettime(CLOCK_MONOTONIC, &ts);
00208    ht = (ts.tv_nsec / 1000000) + 1; /* round to nearest ms */
00209    ts.tv_nsec = ht * 1000000;
00210    cycletime = *(int*)ptr * 1000; /* cycletime in ns */
00211    toff = 0;
00212    dorun = 0;
00213    ec_send_processdata();    
00214    while(1)
00215    {   
00216       /* calculate next cycle start */
00217       add_timespec(&ts, cycletime + toff);
00218       /* wait to cycle start */
00219       rc = clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &ts, &tleft);
00220       if (dorun>0)
00221       {
00222          wkc = ec_receive_processdata(EC_TIMEOUTRET);
00223          
00224          dorun++;
00225          /* if we have some digital output, cycle */
00226          if( digout ) *digout = (uint8) ((dorun / 16) & 0xff); 
00227          
00228          if (ec_slave[0].hasdc)
00229          {   
00230             /* calulate toff to get linux time and DC synced */
00231             ec_sync(ec_DCtime, cycletime, &toff);
00232          }   
00233          ec_send_processdata();    
00234       }   
00235    }    
00236 }
00237 
00238 void ecatcheck( void *ptr )
00239 {
00240     int slave;
00241 
00242     while(1)
00243     {
00244         if( inOP && ((wkc < expectedWKC) || ec_group[currentgroup].docheckstate))
00245         {
00246             if (needlf)
00247             {
00248                needlf = FALSE;
00249                printf("\n");
00250             }
00251             /* one ore more slaves are not responding */
00252             ec_group[currentgroup].docheckstate = FALSE;
00253             ec_readstate();
00254             for (slave = 1; slave <= ec_slavecount; slave++)
00255             {
00256                if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
00257                {
00258                   ec_group[currentgroup].docheckstate = TRUE;
00259                   if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
00260                   {
00261                      printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
00262                      ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
00263                      ec_writestate(slave);
00264                   }
00265                   else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
00266                   {
00267                      printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
00268                      ec_slave[slave].state = EC_STATE_OPERATIONAL;
00269                      ec_writestate(slave);                              
00270                   }
00271                   else if(ec_slave[slave].state > 0)
00272                   {
00273                      if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
00274                      {
00275                         ec_slave[slave].islost = FALSE;
00276                         printf("MESSAGE : slave %d reconfigured\n",slave);                           
00277                      }
00278                   } 
00279                   else if(!ec_slave[slave].islost)
00280                   {
00281                      /* re-check state */
00282                      ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
00283                      if (!ec_slave[slave].state)
00284                      {
00285                         ec_slave[slave].islost = TRUE;
00286                         printf("ERROR : slave %d lost\n",slave);                           
00287                      }
00288                   }
00289                }
00290                if (ec_slave[slave].islost)
00291                {
00292                   if(!ec_slave[slave].state)
00293                   {
00294                      if (ec_recover_slave(slave, EC_TIMEOUTMON))
00295                      {
00296                         ec_slave[slave].islost = FALSE;
00297                         printf("MESSAGE : slave %d recovered\n",slave);                           
00298                      }
00299                   }
00300                   else
00301                   {
00302                      ec_slave[slave].islost = FALSE;
00303                      printf("MESSAGE : slave %d found\n",slave);                           
00304                   }
00305                }
00306             }
00307             if(!ec_group[currentgroup].docheckstate)
00308                printf("OK : all slaves resumed OPERATIONAL.\n");
00309         }
00310         osal_usleep(10000);
00311     }   
00312 }   
00313 
00314 int main(int argc, char *argv[])
00315 {
00316    int iret1, iret2;
00317    int ctime;
00318    struct sched_param    param;
00319    int                   policy = SCHED_OTHER;
00320    
00321    printf("SOEM (Simple Open EtherCAT Master)\nRedundancy test\n");
00322    
00323    memset(&schedp, 0, sizeof(schedp));
00324    /* do not set priority above 49, otherwise sockets are starved */
00325    schedp.sched_priority = 30;
00326    sched_setscheduler(0, SCHED_FIFO, &schedp);
00327    
00328    if (argc > 3)
00329    {      
00330       dorun = 0;
00331       ctime = atoi(argv[3]);
00332 
00333       /* create RT thread */
00334       iret1 = pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);   
00335       memset(&param, 0, sizeof(param));
00336       /* give it higher priority */
00337       param.sched_priority = 40;
00338       iret1 = pthread_setschedparam(thread1, policy, &param);
00339 
00340       /* create thread to handle slave error handling in OP */
00341       iret2 = pthread_create( &thread2, NULL, (void *) &ecatcheck, (void*) &ctime);   
00342 
00343       /* start acyclic part */
00344       redtest(argv[1],argv[2]);
00345    }
00346    else
00347    {
00348       printf("Usage: red_test ifname1 ifname2 cycletime\nifname = eth0 for example\ncycletime in us\n");
00349    }   
00350    
00351    schedp.sched_priority = 0;
00352    sched_setscheduler(0, SCHED_OTHER, &schedp);
00353 
00354    printf("End program\n");
00355 
00356    return (0);
00357 }


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