ebox.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 
00032 #define NSEC_PER_SEC 1000000000
00033 
00034 typedef struct PACKED
00035 {
00036    uint8         status;
00037    uint8         counter;
00038    uint8         din;
00039    int32         ain[2];
00040    uint32        tsain;
00041    int32         enc[2];
00042 } in_EBOXt;   
00043 
00044 typedef struct PACKED
00045 {
00046    uint8         counter;
00047    int16         stream[100];
00048 } in_EBOX_streamt;   
00049 
00050 typedef struct PACKED
00051 {
00052    uint8         control;
00053    uint8         dout;
00054    int16         aout[2];
00055    uint16        pwmout[2];
00056 } out_EBOXt;   
00057 
00058 typedef struct PACKED
00059 {
00060    uint8         control;
00061 } out_EBOX_streamt;   
00062 
00063 // total samples to capture
00064 #define MAXSTREAM 200000
00065 // sample interval in ns, here 8us -> 125kHz
00066 // maximum data rate for E/BOX v1.0.1 is around 150kHz
00067 #define SYNC0TIME 8000
00068 
00069 struct sched_param schedp;
00070 char IOmap[4096];
00071 pthread_t thread1;
00072 struct timeval tv,t1,t2;
00073 int dorun = 0;
00074 int deltat, tmax=0;
00075 int64 toff;
00076 int DCdiff;
00077 int os;
00078 uint32 ob;
00079 int16 ob2;
00080 uint8 ob3;
00081 pthread_cond_t  cond  = PTHREAD_COND_INITIALIZER;
00082 pthread_mutex_t mutex = PTHREAD_MUTEX_INITIALIZER;
00083 int64 integral=0;
00084 uint32 cyclecount;
00085 in_EBOX_streamt  *in_EBOX;
00086 out_EBOX_streamt *out_EBOX;
00087 double     ain[2];
00088 int        ainc;
00089 int        streampos;
00090 int16      stream1[MAXSTREAM];
00091 int16      stream2[MAXSTREAM];
00092 
00093 int output_cvs(char *fname, int length)
00094 {
00095    FILE *fp;
00096  
00097    int  i;
00098 
00099    fp = fopen(fname, "w");
00100    if(fp == NULL) 
00101       return 0;
00102    for (i = 0; i < length; i++)
00103    {
00104       fprintf(fp, "%d %d %d\n", i, stream1[i], stream2[i]);
00105    }
00106    fclose(fp);
00107    
00108    return 1;
00109 }
00110 
00111 void eboxtest(char *ifname)
00112 {
00113    int cnt, i;
00114    
00115    printf("Starting E/BOX test\n");
00116    
00117    /* initialise SOEM, bind socket to ifname */
00118    if (ec_init(ifname))
00119    {   
00120       printf("ec_init on %s succeeded.\n",ifname);
00121       /* find and auto-config slaves */
00122       if ( ec_config_init(FALSE) > 0 )
00123       {
00124          printf("%d slaves found and configured.\n",ec_slavecount);
00125 
00126          // check if first slave is an E/BOX
00127          if (( ec_slavecount >= 1 ) &&
00128              (strcmp(ec_slave[1].name,"E/BOX") == 0))
00129          {
00130             // reprogram PDO mapping to set slave in stream mode
00131             // this can only be done in pre-OP state
00132             os=sizeof(ob2); ob2 = 0x1601;
00133             ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);   
00134             os=sizeof(ob2); ob2 = 0x1a01;
00135             ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);   
00136          }
00137 
00138          ec_config_map(&IOmap);
00139 
00140          ec_configdc();
00141 
00142          /* wait for all slaves to reach SAFE_OP state */
00143          ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE);
00144          
00145          /* configure DC options for every DC capable slave found in the list */
00146          printf("DC capable : %d\n",ec_configdc());
00147          
00148          /* check configuration */
00149          if (( ec_slavecount >= 1 ) &&
00150              (strcmp(ec_slave[1].name,"E/BOX") == 0)
00151             )
00152          {
00153             printf("E/BOX found.\n");
00154 
00155             /* connect struct pointers to slave I/O pointers */
00156             in_EBOX = (in_EBOX_streamt*) ec_slave[1].inputs;
00157             out_EBOX = (out_EBOX_streamt*) ec_slave[1].outputs;
00158 
00159             /* read indevidual slave state and store in ec_slave[] */
00160             ec_readstate();
00161             for(cnt = 1; cnt <= ec_slavecount ; cnt++)
00162             {
00163                printf("Slave:%d Name:%s Output size:%3dbits Input size:%3dbits State:%2d delay:%d.%d\n",
00164                      cnt, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits,
00165                      ec_slave[cnt].state, (int)ec_slave[cnt].pdelay, ec_slave[cnt].hasdc);
00166             }
00167             printf("Request operational state for all slaves\n");
00168 
00169             /* send one processdata cycle to init SM in slaves */   
00170             ec_send_processdata();
00171             ec_receive_processdata(EC_TIMEOUTRET);
00172                
00173             ec_slave[0].state = EC_STATE_OPERATIONAL;
00174             /* request OP state for all slaves */
00175             ec_writestate(0);
00176             /* wait for all slaves to reach OP state */
00177             ec_statecheck(0, EC_STATE_OPERATIONAL,  EC_TIMEOUTSTATE);
00178             if (ec_slave[0].state == EC_STATE_OPERATIONAL )
00179             {
00180                printf("Operational state reached for all slaves.\n");
00181                ain[0] = 0;
00182                ain[1] = 0;
00183                ainc = 0;
00184                dorun = 1;
00185                usleep(100000); // wait for linux to sync on DC
00186                ec_dcsync0(1, TRUE, SYNC0TIME, 0); // SYNC0 on slave 1
00187                /* acyclic loop 20ms */
00188                for(i = 1; i <= 200; i++)
00189                {
00190                   /* read DC difference register for slave 2 */
00191    //               ec_FPRD(ec_slave[1].configadr, ECT_REG_DCSYSDIFF, sizeof(DCdiff), &DCdiff, EC_TIMEOUTRET);
00192    //               if(DCdiff<0) { DCdiff = - (int32)((uint32)DCdiff & 0x7ffffff); }
00193                   printf("PD cycle %5d DCtime %12lld Cnt:%3d Data: %6d %6d %6d %6d %6d %6d %6d %6d \n",
00194                         cyclecount, ec_DCtime, in_EBOX->counter, in_EBOX->stream[0], in_EBOX->stream[1],
00195                          in_EBOX->stream[2], in_EBOX->stream[3], in_EBOX->stream[4], in_EBOX->stream[5],
00196                          in_EBOX->stream[98], in_EBOX->stream[99]);
00197                   usleep(20000);
00198                }
00199                dorun = 0;
00200    //            printf("\nCnt %d : Ain0 = %f  Ain2 = %f\n", ainc, ain[0] / ainc, ain[1] / ainc);
00201             }
00202             else
00203             {
00204                printf("Not all slaves reached operational state.\n");
00205             }         
00206          }
00207          else
00208          {
00209             printf("E/BOX not found in slave configuration.\n");
00210          }   
00211          ec_dcsync0(1, FALSE, 8000, 0); // SYNC0 off
00212          printf("Request safe operational state for all slaves\n");
00213          ec_slave[0].state = EC_STATE_SAFE_OP;
00214          /* request SAFE_OP state for all slaves */
00215          ec_writestate(0);
00216          /* wait for all slaves to reach state */
00217          ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE);
00218          ec_slave[0].state = EC_STATE_PRE_OP;
00219          /* request SAFE_OP state for all slaves */
00220          ec_writestate(0);
00221          /* wait for all slaves to reach state */
00222          ec_statecheck(0, EC_STATE_PRE_OP,  EC_TIMEOUTSTATE);
00223          if (( ec_slavecount >= 1 ) &&
00224              (strcmp(ec_slave[1].name,"E/BOX") == 0))
00225          {
00226             // restore PDO to standard mode
00227             // this can only be done is pre-op state
00228             os=sizeof(ob2); ob2 = 0x1600;
00229             ec_SDOwrite(1,0x1c12,01,FALSE,os,&ob2,EC_TIMEOUTRXM);   
00230             os=sizeof(ob2); ob2 = 0x1a00;
00231             ec_SDOwrite(1,0x1c13,01,FALSE,os,&ob2,EC_TIMEOUTRXM);   
00232          }
00233          printf("Streampos %d\n", streampos);
00234          output_cvs("stream.txt", streampos);
00235       }
00236       else
00237       {
00238          printf("No slaves found!\n");
00239       }
00240       printf("End E/BOX, close socket\n");
00241       /* stop SOEM, close socket */
00242       ec_close();
00243    }
00244    else
00245    {
00246       printf("No socket connection on %s\nExcecute as root\n",ifname);
00247    }   
00248 }   
00249 
00250 /* add ns to timespec */
00251 void add_timespec(struct timespec *ts, int64 addtime)
00252 {
00253    int64 sec, nsec;
00254    
00255    nsec = addtime % NSEC_PER_SEC;
00256    sec = (addtime - nsec) / NSEC_PER_SEC;
00257    ts->tv_sec += sec;
00258    ts->tv_nsec += nsec;
00259    if ( ts->tv_nsec > NSEC_PER_SEC ) 
00260    { 
00261       nsec = ts->tv_nsec % NSEC_PER_SEC;
00262       ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
00263       ts->tv_nsec = nsec;
00264    }   
00265 }   
00266 
00267 /* PI calculation to get linux time synced to DC time */
00268 void ec_sync(int64 reftime, int64 cycletime , int64 *offsettime)
00269 {
00270    int64 delta;
00271    /* set linux sync point 50us later than DC sync, just as example */
00272    delta = (reftime - 50000) % cycletime;
00273    if(delta> (cycletime /2)) { delta= delta - cycletime; }
00274    if(delta>0){ integral++; }
00275    if(delta<0){ integral--; }
00276    *offsettime = -(delta / 100) - (integral /20);
00277 }   
00278 
00279 /* RT EtherCAT thread */
00280 void ecatthread( void *ptr )
00281 {
00282    struct timespec   ts;
00283    struct timeval    tp;
00284    int rc;
00285    int ht;
00286    int i;
00287    int pcounter = 0;
00288    int64 cycletime;
00289    
00290    rc = pthread_mutex_lock(&mutex);
00291    rc =  gettimeofday(&tp, NULL);
00292 
00293     /* Convert from timeval to timespec */
00294    ts.tv_sec  = tp.tv_sec;
00295    ht = (tp.tv_usec / 1000) + 1; /* round to nearest ms */
00296    ts.tv_nsec = ht * 1000000;
00297    cycletime = *(int*)ptr * 1000; /* cycletime in ns */
00298    toff = 0;
00299    dorun = 0;
00300    while(1)
00301    {   
00302       /* calculate next cycle start */
00303       add_timespec(&ts, cycletime + toff);
00304       /* wait to cycle start */
00305       rc = pthread_cond_timedwait(&cond, &mutex, &ts);
00306       if (dorun>0)
00307       {
00308          rc =  gettimeofday(&tp, NULL);
00309 
00310          ec_send_processdata();
00311 
00312          ec_receive_processdata(EC_TIMEOUTRET);
00313 
00314          cyclecount++;
00315 
00316          
00317          if((in_EBOX->counter != pcounter) && (streampos < (MAXSTREAM - 1)))
00318          {
00319             // check if we have timing problems in master
00320             // if so, overwrite stream data so it shows up clearly in plots.
00321             if(in_EBOX->counter > (pcounter + 1))
00322             {
00323                for(i = 0 ; i < 50 ; i++)
00324                {
00325                   stream1[streampos]   = 20000;
00326                   stream2[streampos++] = -20000;
00327                }
00328             }
00329             else
00330             {
00331                for(i = 0 ; i < 50 ; i++)
00332                {
00333                   stream1[streampos]   = in_EBOX->stream[i * 2];
00334                   stream2[streampos++] = in_EBOX->stream[(i * 2) + 1];
00335                }
00336             }
00337             pcounter = in_EBOX->counter;
00338          }
00339                       
00340          /* calulate toff to get linux time and DC synced */
00341          ec_sync(ec_DCtime, cycletime, &toff);
00342       }   
00343    }    
00344 }
00345 
00346 int main(int argc, char *argv[])
00347 {
00348    int iret1;
00349    int ctime;
00350    struct sched_param    param;
00351    int                   policy = SCHED_OTHER;
00352    
00353    printf("SOEM (Simple Open EtherCAT Master)\nE/BOX test\n");
00354    
00355    memset(&schedp, 0, sizeof(schedp));
00356    /* do not set priority above 49, otherwise sockets are starved */
00357    schedp.sched_priority = 30;
00358    sched_setscheduler(0, SCHED_FIFO, &schedp);
00359 
00360    do
00361    {
00362       usleep(1000);
00363    }
00364    while (dorun);
00365    
00366    if (argc > 1)
00367    {      
00368       dorun = 1;
00369       if( argc > 2)
00370          ctime = atoi(argv[2]);
00371       else
00372          ctime = 1000; // 1ms cycle time
00373       /* create RT thread */
00374       iret1 = pthread_create( &thread1, NULL, (void *) &ecatthread, (void*) &ctime);   
00375       memset(&param, 0, sizeof(param));
00376       /* give it higher priority */
00377       param.sched_priority = 40;
00378       iret1 = pthread_setschedparam(thread1, policy, &param);
00379 
00380       /* start acyclic part */
00381       eboxtest(argv[1]);
00382    }
00383    else
00384    {
00385       printf("Usage: ebox ifname [cycletime]\nifname = eth0 for example\ncycletime in us\n");
00386    }   
00387    
00388    schedp.sched_priority = 0;
00389    sched_setscheduler(0, SCHED_OTHER, &schedp);
00390 
00391    printf("End program\n");
00392    
00393    return (0);
00394 }


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