00001
00014 #include <stdio.h>
00015 #include <string.h>
00016
00017 #include "ethercat_soem/ethercattype.h"
00018 #include "ethercat_soem/nicdrv.h"
00019 #include "ethercat_soem/ethercatbase.h"
00020 #include "ethercat_soem/ethercatmain.h"
00021 #include "ethercat_soem/ethercatconfig.h"
00022 #include "ethercat_soem/ethercatcoe.h"
00023 #include "ethercat_soem/ethercatdc.h"
00024 #include "ethercat_soem/ethercatprint.h"
00025
00026 char IOmap[4096];
00027 ec_ODlistt ODlist;
00028 ec_OElistt OElist;
00029 boolean printSDO = FALSE;
00030 boolean printMAP = FALSE;
00031 char usdo[128];
00032 char hstr[1024];
00033
00034 char* dtype2string(uint16 dtype)
00035 {
00036 switch(dtype)
00037 {
00038 case ECT_BOOLEAN:
00039 sprintf(hstr, "BOOLEAN");
00040 break;
00041 case ECT_INTEGER8:
00042 sprintf(hstr, "INTEGER8");
00043 break;
00044 case ECT_INTEGER16:
00045 sprintf(hstr, "INTEGER16");
00046 break;
00047 case ECT_INTEGER32:
00048 sprintf(hstr, "INTEGER32");
00049 break;
00050 case ECT_INTEGER24:
00051 sprintf(hstr, "INTEGER24");
00052 break;
00053 case ECT_INTEGER64:
00054 sprintf(hstr, "INTEGER64");
00055 break;
00056 case ECT_UNSIGNED8:
00057 sprintf(hstr, "UNSIGNED8");
00058 break;
00059 case ECT_UNSIGNED16:
00060 sprintf(hstr, "UNSIGNED16");
00061 break;
00062 case ECT_UNSIGNED32:
00063 sprintf(hstr, "UNSIGNED32");
00064 break;
00065 case ECT_UNSIGNED24:
00066 sprintf(hstr, "UNSIGNED24");
00067 break;
00068 case ECT_UNSIGNED64:
00069 sprintf(hstr, "UNSIGNED64");
00070 break;
00071 case ECT_REAL32:
00072 sprintf(hstr, "REAL32");
00073 break;
00074 case ECT_REAL64:
00075 sprintf(hstr, "REAL64");
00076 break;
00077 case ECT_BIT1:
00078 sprintf(hstr, "BIT1");
00079 break;
00080 case ECT_BIT2:
00081 sprintf(hstr, "BIT2");
00082 break;
00083 case ECT_BIT3:
00084 sprintf(hstr, "BIT3");
00085 break;
00086 case ECT_BIT4:
00087 sprintf(hstr, "BIT4");
00088 break;
00089 case ECT_BIT5:
00090 sprintf(hstr, "BIT5");
00091 break;
00092 case ECT_BIT6:
00093 sprintf(hstr, "BIT6");
00094 break;
00095 case ECT_BIT7:
00096 sprintf(hstr, "BIT7");
00097 break;
00098 case ECT_BIT8:
00099 sprintf(hstr, "BIT8");
00100 break;
00101 case ECT_VISIBLE_STRING:
00102 sprintf(hstr, "VISIBLE_STRING");
00103 break;
00104 case ECT_OCTET_STRING:
00105 sprintf(hstr, "OCTET_STRING");
00106 break;
00107 default:
00108 sprintf(hstr, "Type 0x%4.4X", dtype);
00109 }
00110 return hstr;
00111 }
00112
00113 char* SDO2string(uint16 slave, uint16 index, uint8 subidx, uint16 dtype)
00114 {
00115 int l = sizeof(usdo) - 1, i;
00116 uint8 *u8;
00117 int8 *i8;
00118 uint16 *u16;
00119 int16 *i16;
00120 uint32 *u32;
00121 int32 *i32;
00122 uint64 *u64;
00123 int64 *i64;
00124 float *sr;
00125 double *dr;
00126 char es[32];
00127
00128 memset(&usdo, 0, 128);
00129 ec_SDOread(slave, index, subidx, FALSE, &l, &usdo, EC_TIMEOUTRXM);
00130 if (EcatError)
00131 {
00132 return ec_elist2string();
00133 }
00134 else
00135 {
00136 switch(dtype)
00137 {
00138 case ECT_BOOLEAN:
00139 u8 = (uint8*) &usdo[0];
00140 if (*u8) sprintf(hstr, "TRUE");
00141 else sprintf(hstr, "FALSE");
00142 break;
00143 case ECT_INTEGER8:
00144 i8 = (int8*) &usdo[0];
00145 sprintf(hstr, "0x%2.2x %d", *i8, *i8);
00146 break;
00147 case ECT_INTEGER16:
00148 i16 = (int16*) &usdo[0];
00149 sprintf(hstr, "0x%4.4x %d", *i16, *i16);
00150 break;
00151 case ECT_INTEGER32:
00152 case ECT_INTEGER24:
00153 i32 = (int32*) &usdo[0];
00154 sprintf(hstr, "0x%8.8x %d", *i32, *i32);
00155 break;
00156 case ECT_INTEGER64:
00157 i64 = (int64*) &usdo[0];
00158 sprintf(hstr, "0x%16.16llx %lld", *i64, *i64);
00159 break;
00160 case ECT_UNSIGNED8:
00161 u8 = (uint8*) &usdo[0];
00162 sprintf(hstr, "0x%2.2x %u", *u8, *u8);
00163 break;
00164 case ECT_UNSIGNED16:
00165 u16 = (uint16*) &usdo[0];
00166 sprintf(hstr, "0x%4.4x %u", *u16, *u16);
00167 break;
00168 case ECT_UNSIGNED32:
00169 case ECT_UNSIGNED24:
00170 u32 = (uint32*) &usdo[0];
00171 sprintf(hstr, "0x%8.8x %u", *u32, *u32);
00172 break;
00173 case ECT_UNSIGNED64:
00174 u64 = (uint64*) &usdo[0];
00175 sprintf(hstr, "0x%16.16llx %llu", *u64, *u64);
00176 break;
00177 case ECT_REAL32:
00178 sr = (float*) &usdo[0];
00179 sprintf(hstr, "%f", *sr);
00180 break;
00181 case ECT_REAL64:
00182 dr = (double*) &usdo[0];
00183 sprintf(hstr, "%f", *dr);
00184 break;
00185 case ECT_BIT1:
00186 case ECT_BIT2:
00187 case ECT_BIT3:
00188 case ECT_BIT4:
00189 case ECT_BIT5:
00190 case ECT_BIT6:
00191 case ECT_BIT7:
00192 case ECT_BIT8:
00193 u8 = (uint8*) &usdo[0];
00194 sprintf(hstr, "0x%x", *u8);
00195 break;
00196 case ECT_VISIBLE_STRING:
00197 strcpy(hstr, usdo);
00198 break;
00199 case ECT_OCTET_STRING:
00200 hstr[0] = 0x00;
00201 for (i = 0 ; i < l ; i++)
00202 {
00203 sprintf(es, "0x%2.2x ", usdo[i]);
00204 strcat( hstr, es);
00205 }
00206 break;
00207 default:
00208 sprintf(hstr, "Unknown type");
00209 }
00210 return hstr;
00211 }
00212 }
00213
00215 int si_PDOassign(uint16 slave, uint16 PDOassign, int mapoffset, int bitoffset)
00216 {
00217 uint16 idxloop, nidx, subidxloop, rdat, idx, subidx;
00218 uint8 subcnt;
00219 int wkc, bsize = 0, rdl;
00220 int32 rdat2;
00221 uint8 bitlen, obj_subidx;
00222 uint16 obj_idx;
00223 int abs_offset, abs_bit;
00224
00225 rdl = sizeof(rdat); rdat = 0;
00226
00227 wkc = ec_SDOread(slave, PDOassign, 0x00, FALSE, &rdl, &rdat, EC_TIMEOUTRXM);
00228 rdat = etohs(rdat);
00229
00230 if ((wkc > 0) && (rdat > 0))
00231 {
00232
00233 nidx = rdat;
00234 bsize = 0;
00235
00236 for (idxloop = 1; idxloop <= nidx; idxloop++)
00237 {
00238 rdl = sizeof(rdat); rdat = 0;
00239
00240 wkc = ec_SDOread(slave, PDOassign, (uint8)idxloop, FALSE, &rdl, &rdat, EC_TIMEOUTRXM);
00241
00242 idx = etohl(rdat);
00243 if (idx > 0)
00244 {
00245 rdl = sizeof(subcnt); subcnt = 0;
00246
00247 wkc = ec_SDOread(slave,idx, 0x00, FALSE, &rdl, &subcnt, EC_TIMEOUTRXM);
00248 subidx = subcnt;
00249
00250 for (subidxloop = 1; subidxloop <= subidx; subidxloop++)
00251 {
00252 rdl = sizeof(rdat2); rdat2 = 0;
00253
00254 wkc = ec_SDOread(slave, idx, (uint8)subidxloop, FALSE, &rdl, &rdat2, EC_TIMEOUTRXM);
00255 rdat2 = etohl(rdat2);
00256
00257 bitlen = LO_BYTE(rdat2);
00258 bsize += bitlen;
00259 obj_idx = (uint16)(rdat2 >> 16);
00260 obj_subidx = (uint8)((rdat2 >> 8) & 0x000000ff);
00261 abs_offset = mapoffset + (bitoffset / 8);
00262 abs_bit = bitoffset % 8;
00263 ODlist.Slave = slave;
00264 ODlist.Index[0] = obj_idx;
00265 OElist.Entries = 0;
00266 wkc = 0;
00267
00268 if(obj_idx || obj_subidx)
00269 wkc = ec_readOEsingle(0, obj_subidx, &ODlist, &OElist);
00270 printf(" [0x%4.4X.%1d] 0x%4.4X:0x%2.2X 0x%2.2X", abs_offset, abs_bit, obj_idx, obj_subidx, bitlen);
00271 if((wkc > 0) && OElist.Entries)
00272 {
00273 printf(" %-12s %s\n", dtype2string(OElist.DataType[obj_subidx]), OElist.Name[obj_subidx]);
00274 }
00275 else
00276 printf("\n");
00277 bitoffset += bitlen;
00278 };
00279 };
00280 };
00281 };
00282
00283 return bsize;
00284 }
00285
00286 int si_map_sdo(int slave)
00287 {
00288 int wkc, rdl;
00289 int retVal = 0;
00290 uint8 nSM, iSM, tSM;
00291 int Tsize, outputs_bo, inputs_bo;
00292 uint8 SMt_bug_add;
00293
00294 printf("PDO mapping according to CoE :\n");
00295 SMt_bug_add = 0;
00296 outputs_bo = 0;
00297 inputs_bo = 0;
00298 rdl = sizeof(nSM); nSM = 0;
00299
00300 wkc = ec_SDOread(slave, ECT_SDO_SMCOMMTYPE, 0x00, FALSE, &rdl, &nSM, EC_TIMEOUTRXM);
00301
00302 if ((wkc > 0) && (nSM > 2))
00303 {
00304
00305 nSM--;
00306
00307 if (nSM > EC_MAXSM)
00308 nSM = EC_MAXSM;
00309
00310 for (iSM = 2 ; iSM <= nSM ; iSM++)
00311 {
00312 rdl = sizeof(tSM); tSM = 0;
00313
00314 wkc = ec_SDOread(slave, ECT_SDO_SMCOMMTYPE, iSM + 1, FALSE, &rdl, &tSM, EC_TIMEOUTRXM);
00315 if (wkc > 0)
00316 {
00317 if((iSM == 2) && (tSM == 2))
00318 {
00319 SMt_bug_add = 1;
00320 printf("Activated SM type workaround, possible incorrect mapping.\n");
00321 }
00322 if(tSM)
00323 tSM += SMt_bug_add;
00324
00325 if (tSM == 3)
00326 {
00327
00328 printf(" SM%1d outputs\n addr b index: sub bitl data_type name\n", iSM);
00329 Tsize = si_PDOassign(slave, ECT_SDO_PDOASSIGN + iSM, (int)(ec_slave[slave].outputs - (uint8 *)&IOmap[0]), outputs_bo );
00330 outputs_bo += Tsize;
00331 }
00332 if (tSM == 4)
00333 {
00334
00335 printf(" SM%1d inputs\n addr b index: sub bitl data_type name\n", iSM);
00336 Tsize = si_PDOassign(slave, ECT_SDO_PDOASSIGN + iSM, (int)(ec_slave[slave].inputs - (uint8 *)&IOmap[0]), inputs_bo );
00337 inputs_bo += Tsize;
00338 }
00339 }
00340 }
00341 }
00342
00343
00344 if ((outputs_bo > 0) || (inputs_bo > 0))
00345 retVal = 1;
00346 return retVal;
00347 }
00348
00349 int si_siiPDO(uint16 slave, uint8 t, int mapoffset, int bitoffset)
00350 {
00351 uint16 a , w, c, e, er, Size;
00352 uint8 eectl;
00353 uint16 obj_idx;
00354 uint8 obj_subidx;
00355 uint8 obj_name;
00356 uint8 obj_datatype;
00357 uint8 bitlen;
00358 int totalsize;
00359 ec_eepromPDOt eepPDO;
00360 ec_eepromPDOt *PDO;
00361 int abs_offset, abs_bit;
00362 char str_name[EC_MAXNAME + 1];
00363
00364 eectl = ec_slave[slave].eep_pdi;
00365 Size = 0;
00366 totalsize = 0;
00367 PDO = &eepPDO;
00368 PDO->nPDO = 0;
00369 PDO->Length = 0;
00370 PDO->Index[1] = 0;
00371 for (c = 0 ; c < EC_MAXSM ; c++) PDO->SMbitsize[c] = 0;
00372 if (t > 1)
00373 t = 1;
00374 PDO->Startpos = ec_siifind(slave, ECT_SII_PDO + t);
00375 if (PDO->Startpos > 0)
00376 {
00377 a = PDO->Startpos;
00378 w = ec_siigetbyte(slave, a++);
00379 w += (ec_siigetbyte(slave, a++) << 8);
00380 PDO->Length = w;
00381 c = 1;
00382
00383 do
00384 {
00385 PDO->nPDO++;
00386 PDO->Index[PDO->nPDO] = ec_siigetbyte(slave, a++);
00387 PDO->Index[PDO->nPDO] += (ec_siigetbyte(slave, a++) << 8);
00388 PDO->BitSize[PDO->nPDO] = 0;
00389 c++;
00390
00391 e = ec_siigetbyte(slave, a++);
00392 PDO->SyncM[PDO->nPDO] = ec_siigetbyte(slave, a++);
00393 a++;
00394 obj_name = ec_siigetbyte(slave, a++);
00395 a += 2;
00396 c += 2;
00397 if (PDO->SyncM[PDO->nPDO] < EC_MAXSM)
00398 {
00399 str_name[0] = 0;
00400 if(obj_name)
00401 ec_siistring(str_name, slave, obj_name);
00402 if (t)
00403 printf(" SM%1d RXPDO 0x%4.4X %s\n", PDO->SyncM[PDO->nPDO], PDO->Index[PDO->nPDO], str_name);
00404 else
00405 printf(" SM%1d TXPDO 0x%4.4X %s\n", PDO->SyncM[PDO->nPDO], PDO->Index[PDO->nPDO], str_name);
00406 printf(" addr b index: sub bitl data_type name\n");
00407
00408 for (er = 1; er <= e; er++)
00409 {
00410 c += 4;
00411 obj_idx = ec_siigetbyte(slave, a++);
00412 obj_idx += (ec_siigetbyte(slave, a++) << 8);
00413 obj_subidx = ec_siigetbyte(slave, a++);
00414 obj_name = ec_siigetbyte(slave, a++);
00415 obj_datatype = ec_siigetbyte(slave, a++);
00416 bitlen = ec_siigetbyte(slave, a++);
00417 abs_offset = mapoffset + (bitoffset / 8);
00418 abs_bit = bitoffset % 8;
00419
00420 PDO->BitSize[PDO->nPDO] += bitlen;
00421 a += 2;
00422
00423 str_name[0] = 0;
00424 if(obj_name)
00425 ec_siistring(str_name, slave, obj_name);
00426
00427 printf(" [0x%4.4X.%1d] 0x%4.4X:0x%2.2X 0x%2.2X", abs_offset, abs_bit, obj_idx, obj_subidx, bitlen);
00428 printf(" %-12s %s\n", dtype2string(obj_datatype), str_name);
00429 bitoffset += bitlen;
00430 totalsize += bitlen;
00431 }
00432 PDO->SMbitsize[ PDO->SyncM[PDO->nPDO] ] += PDO->BitSize[PDO->nPDO];
00433 Size += PDO->BitSize[PDO->nPDO];
00434 c++;
00435 }
00436 else
00437 {
00438 c += 4 * e;
00439 a += 8 * e;
00440 c++;
00441 }
00442 if (PDO->nPDO >= (EC_MAXEEPDO - 1)) c = PDO->Length;
00443 }
00444 while (c < PDO->Length);
00445 }
00446 if (eectl) ec_eeprom2pdi(slave);
00447 return totalsize;
00448 }
00449
00450
00451 int si_map_sii(int slave)
00452 {
00453 int retVal = 0;
00454 int Tsize, outputs_bo, inputs_bo;
00455
00456 printf("PDO mapping according to SII :\n");
00457
00458 outputs_bo = 0;
00459 inputs_bo = 0;
00460
00461 Tsize = si_siiPDO(slave, 1, (int)(ec_slave[slave].outputs - (uint8*)&IOmap), outputs_bo );
00462 outputs_bo += Tsize;
00463
00464 Tsize = si_siiPDO(slave, 0, (int)(ec_slave[slave].inputs - (uint8*)&IOmap), inputs_bo );
00465 inputs_bo += Tsize;
00466
00467 if ((outputs_bo > 0) || (inputs_bo > 0))
00468 retVal = 1;
00469 return retVal;
00470 }
00471
00472 void si_sdo(int cnt)
00473 {
00474 int i, j;
00475
00476 ODlist.Entries = 0;
00477 memset(&ODlist, 0, sizeof(ODlist));
00478 if( ec_readODlist(cnt, &ODlist))
00479 {
00480 printf(" CoE Object Description found, %d entries.\n",ODlist.Entries);
00481 for( i = 0 ; i < ODlist.Entries ; i++)
00482 {
00483 ec_readODdescription(i, &ODlist);
00484 while(EcatError) printf("%s", ec_elist2string());
00485 printf(" Index: %4.4x Datatype: %4.4x Objectcode: %2.2x Name: %s\n",
00486 ODlist.Index[i], ODlist.DataType[i], ODlist.ObjectCode[i], ODlist.Name[i]);
00487 memset(&OElist, 0, sizeof(OElist));
00488 ec_readOE(i, &ODlist, &OElist);
00489 while(EcatError) printf("%s", ec_elist2string());
00490 for( j = 0 ; j < ODlist.MaxSub[i]+1 ; j++)
00491 {
00492 if ((OElist.DataType[j] > 0) && (OElist.BitLength[j] > 0))
00493 {
00494 printf(" Sub: %2.2x Datatype: %4.4x Bitlength: %4.4x Obj.access: %4.4x Name: %s\n",
00495 j, OElist.DataType[j], OElist.BitLength[j], OElist.ObjAccess[j], OElist.Name[j]);
00496 if ((OElist.ObjAccess[j] & 0x0007))
00497 {
00498 printf(" Value :%s\n", SDO2string(cnt, ODlist.Index[i], j, OElist.DataType[j]));
00499 }
00500 }
00501 }
00502 }
00503 }
00504 else
00505 {
00506 while(EcatError) printf("%s", ec_elist2string());
00507 }
00508 }
00509
00510 void slaveinfo(char *ifname)
00511 {
00512 int cnt, i, j, nSM;
00513 uint16 ssigen;
00514 int expectedWKC;
00515
00516 printf("Starting slaveinfo\n");
00517
00518
00519 if (ec_init(ifname))
00520 {
00521 printf("ec_init on %s succeeded.\n",ifname);
00522
00523 if ( ec_config(FALSE, &IOmap) > 0 )
00524 {
00525 ec_configdc();
00526 while(EcatError) printf("%s", ec_elist2string());
00527 printf("%d slaves found and configured.\n",ec_slavecount);
00528 expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
00529 printf("Calculated workcounter %d\n", expectedWKC);
00530
00531 ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 3);
00532 if (ec_slave[0].state != EC_STATE_SAFE_OP )
00533 {
00534 printf("Not all slaves reached safe operational state.\n");
00535 ec_readstate();
00536 for(i = 1; i<=ec_slavecount ; i++)
00537 {
00538 if(ec_slave[i].state != EC_STATE_SAFE_OP)
00539 {
00540 printf("Slave %d State=%2x StatusCode=%4x : %s\n",
00541 i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
00542 }
00543 }
00544 }
00545
00546
00547 ec_readstate();
00548 for( cnt = 1 ; cnt <= ec_slavecount ; cnt++)
00549 {
00550 printf("\nSlave:%d\n Name:%s\n Output size: %dbits\n Input size: %dbits\n State: %d\n Delay: %d[ns]\n Has DC: %d\n",
00551 cnt, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits,
00552 ec_slave[cnt].state, ec_slave[cnt].pdelay, ec_slave[cnt].hasdc);
00553 if (ec_slave[cnt].hasdc) printf(" DCParentport:%d\n", ec_slave[cnt].parentport);
00554 printf(" Activeports:%d.%d.%d.%d\n", (ec_slave[cnt].activeports & 0x01) > 0 ,
00555 (ec_slave[cnt].activeports & 0x02) > 0 ,
00556 (ec_slave[cnt].activeports & 0x04) > 0 ,
00557 (ec_slave[cnt].activeports & 0x08) > 0 );
00558 printf(" Configured address: %4.4x\n", ec_slave[cnt].configadr);
00559 printf(" Man: %8.8x ID: %8.8x Rev: %8.8x\n", (int)ec_slave[cnt].eep_man, (int)ec_slave[cnt].eep_id, (int)ec_slave[cnt].eep_rev);
00560 for(nSM = 0 ; nSM < EC_MAXSM ; nSM++)
00561 {
00562 if(ec_slave[cnt].SM[nSM].StartAddr > 0)
00563 printf(" SM%1d A:%4.4x L:%4d F:%8.8x Type:%d\n",nSM, ec_slave[cnt].SM[nSM].StartAddr, ec_slave[cnt].SM[nSM].SMlength,
00564 (int)ec_slave[cnt].SM[nSM].SMflags, ec_slave[cnt].SMtype[nSM]);
00565 }
00566 for(j = 0 ; j < ec_slave[cnt].FMMUunused ; j++)
00567 {
00568 printf(" FMMU%1d Ls:%8.8x Ll:%4d Lsb:%d Leb:%d Ps:%4.4x Psb:%d Ty:%2.2x Act:%2.2x\n", j,
00569 (int)ec_slave[cnt].FMMU[j].LogStart, ec_slave[cnt].FMMU[j].LogLength, ec_slave[cnt].FMMU[j].LogStartbit,
00570 ec_slave[cnt].FMMU[j].LogEndbit, ec_slave[cnt].FMMU[j].PhysStart, ec_slave[cnt].FMMU[j].PhysStartBit,
00571 ec_slave[cnt].FMMU[j].FMMUtype, ec_slave[cnt].FMMU[j].FMMUactive);
00572 }
00573 printf(" FMMUfunc 0:%d 1:%d 2:%d 3:%d\n",
00574 ec_slave[cnt].FMMU0func, ec_slave[cnt].FMMU2func, ec_slave[cnt].FMMU2func, ec_slave[cnt].FMMU3func);
00575 printf(" MBX length wr: %d rd: %d MBX protocols : %2.2x\n", ec_slave[cnt].mbx_l, ec_slave[cnt].mbx_rl, ec_slave[cnt].mbx_proto);
00576 ssigen = ec_siifind(cnt, ECT_SII_GENERAL);
00577
00578 if (ssigen)
00579 {
00580 ec_slave[cnt].CoEdetails = ec_siigetbyte(cnt, ssigen + 0x07);
00581 ec_slave[cnt].FoEdetails = ec_siigetbyte(cnt, ssigen + 0x08);
00582 ec_slave[cnt].EoEdetails = ec_siigetbyte(cnt, ssigen + 0x09);
00583 ec_slave[cnt].SoEdetails = ec_siigetbyte(cnt, ssigen + 0x0a);
00584 if((ec_siigetbyte(cnt, ssigen + 0x0d) & 0x02) > 0)
00585 {
00586 ec_slave[cnt].blockLRW = 1;
00587 ec_slave[0].blockLRW++;
00588 }
00589 ec_slave[cnt].Ebuscurrent = ec_siigetbyte(cnt, ssigen + 0x0e);
00590 ec_slave[cnt].Ebuscurrent += ec_siigetbyte(cnt, ssigen + 0x0f) << 8;
00591 ec_slave[0].Ebuscurrent += ec_slave[cnt].Ebuscurrent;
00592 }
00593 printf(" CoE details: %2.2x FoE details: %2.2x EoE details: %2.2x SoE details: %2.2x\n",
00594 ec_slave[cnt].CoEdetails, ec_slave[cnt].FoEdetails, ec_slave[cnt].EoEdetails, ec_slave[cnt].SoEdetails);
00595 printf(" Ebus current: %d[mA]\n only LRD/LWR:%d\n",
00596 ec_slave[cnt].Ebuscurrent, ec_slave[cnt].blockLRW);
00597 if ((ec_slave[cnt].mbx_proto & 0x04) && printSDO)
00598 si_sdo(cnt);
00599 if(printMAP)
00600 {
00601 if (ec_slave[cnt].mbx_proto & 0x04)
00602 si_map_sdo(cnt);
00603 else
00604 si_map_sii(cnt);
00605 }
00606 }
00607 }
00608 else
00609 {
00610 printf("No slaves found!\n");
00611 }
00612 printf("End slaveinfo, close socket\n");
00613
00614 ec_close();
00615 }
00616 else
00617 {
00618 printf("No socket connection on %s\nExcecute as root\n",ifname);
00619 }
00620 }
00621
00622 int main(int argc, char *argv[])
00623 {
00624 printf("SOEM (Simple Open EtherCAT Master)\nSlaveinfo\n");
00625
00626 if (argc > 1)
00627 {
00628 if ((argc > 2) && (strncmp(argv[2], "-sdo", sizeof("-sdo")) == 0)) printSDO = TRUE;
00629 if ((argc > 2) && (strncmp(argv[2], "-map", sizeof("-map")) == 0)) printMAP = TRUE;
00630
00631 slaveinfo(argv[1]);
00632 }
00633 else
00634 {
00635 printf("Usage: slaveinfo ifname [options]\nifname = eth0 for example\nOptions :\n -sdo : print SDO info\n -map : print mapping\n");
00636 }
00637
00638 printf("End program\n");
00639 return (0);
00640 }