firm_update.c
Go to the documentation of this file.
00001 
00015 #include <stdio.h>
00016 #include <stdlib.h>
00017 #include <string.h>
00018 #include <sys/time.h>
00019 #include <unistd.h>
00020 
00021 #include "ethercat_soem/ethercattype.h"
00022 #include "ethercat_soem/nicdrv.h"
00023 #include "ethercat_soem/ethercatbase.h"
00024 #include "ethercat_soem/ethercatmain.h"
00025 #include "ethercat_soem/ethercatcoe.h"
00026 #include "ethercat_soem/ethercatfoe.h"
00027 #include "ethercat_soem/ethercatconfig.h"
00028 #include "ethercat_soem/ethercatprint.h"
00029 
00030 #define FWBUFSIZE (8 * 1024 * 1024)
00031 
00032 uint8 ob;
00033 uint16 ow;
00034 uint32 data;
00035 char filename[256];
00036 char filebuffer[FWBUFSIZE]; // 8MB buffer
00037 int filesize;
00038 int j;
00039 uint16 argslave;
00040 
00041 int input_bin(char *fname, int *length)
00042 {
00043     FILE *fp;
00044  
00045         int cc = 0, c;
00046 
00047     fp = fopen(fname, "rb");
00048     if(fp == NULL) 
00049         return 0;
00050         while (((c = fgetc(fp)) != EOF) && (cc < FWBUFSIZE))
00051                 filebuffer[cc++] = (uint8)c;
00052         *length = cc;
00053         fclose(fp);
00054         return 1;
00055 }
00056 
00057 
00058 void boottest(char *ifname, uint16 slave, char *filename)
00059 {       
00060         printf("Starting firmware update example\n");
00061         
00062         /* initialise SOEM, bind socket to ifname */
00063         if (ec_init(ifname))
00064         {       
00065                 printf("ec_init on %s succeeded.\n",ifname);
00066                 /* find and auto-config slaves */
00067 
00068 
00069             if ( ec_config_init(FALSE) > 0 )
00070                 {
00071                         printf("%d slaves found and configured.\n",ec_slavecount);
00072                         
00073                         printf("Request init state for slave %d\n", slave);
00074                         ec_slave[slave].state = EC_STATE_INIT;
00075                         ec_writestate(slave);
00076 
00077                         /* wait for slave to reach INIT state */
00078                         ec_statecheck(slave, EC_STATE_INIT,  EC_TIMEOUTSTATE * 4);
00079                         printf("Slave %d state to INIT.\n", slave);
00080 
00081                         /* read BOOT mailbox data, master -> slave */
00082                         data = ec_readeeprom(slave, ECT_SII_BOOTRXMBX, EC_TIMEOUTEEP);
00083                         ec_slave[slave].SM[0].StartAddr = (uint16)LO_WORD(data);
00084                         ec_slave[slave].SM[0].SMlength = (uint16)HI_WORD(data);
00085                         /* store boot write mailbox address */
00086                         ec_slave[slave].mbx_wo = (uint16)LO_WORD(data);
00087                         /* store boot write mailbox size */
00088                         ec_slave[slave].mbx_l = (uint16)HI_WORD(data);
00089 
00090                         /* read BOOT mailbox data, slave -> master */
00091                         data = ec_readeeprom(slave, ECT_SII_BOOTTXMBX, EC_TIMEOUTEEP);
00092                         ec_slave[slave].SM[1].StartAddr = (uint16)LO_WORD(data);
00093                         ec_slave[slave].SM[1].SMlength = (uint16)HI_WORD(data);
00094                         /* store boot read mailbox address */
00095                         ec_slave[slave].mbx_ro = (uint16)LO_WORD(data);
00096                         /* store boot read mailbox size */
00097                         ec_slave[slave].mbx_rl = (uint16)HI_WORD(data);
00098 
00099                         printf(" SM0 A:%4.4x L:%4d F:%8.8x\n", ec_slave[slave].SM[0].StartAddr, ec_slave[slave].SM[0].SMlength,
00100                             (int)ec_slave[slave].SM[0].SMflags);
00101                         printf(" SM1 A:%4.4x L:%4d F:%8.8x\n", ec_slave[slave].SM[1].StartAddr, ec_slave[slave].SM[1].SMlength,
00102                             (int)ec_slave[slave].SM[1].SMflags);
00103                         /* program SM0 mailbox in for slave */
00104                         ec_FPWR (ec_slave[slave].configadr, ECT_REG_SM0, sizeof(ec_smt), &ec_slave[slave].SM[0], EC_TIMEOUTRET);
00105                         /* program SM1 mailbox out for slave */
00106                         ec_FPWR (ec_slave[slave].configadr, ECT_REG_SM1, sizeof(ec_smt), &ec_slave[slave].SM[1], EC_TIMEOUTRET);
00107                         
00108                         printf("Request BOOT state for slave %d\n", slave);
00109                         ec_slave[slave].state = EC_STATE_BOOT;
00110                         ec_writestate(slave);
00111 
00112                         /* wait for slave to reach BOOT state */
00113                         if (ec_statecheck(slave, EC_STATE_BOOT,  EC_TIMEOUTSTATE * 10) == EC_STATE_BOOT)
00114                         {
00115                                 printf("Slave %d state to BOOT.\n", slave);
00116 
00117                                 if (input_bin(filename, &filesize))
00118                                 {
00119                                         printf("File read OK, %d bytes.\n",filesize);
00120                                         printf("FoE write....");
00121                                         j = ec_FOEwrite(slave, filename, 0, filesize , &filebuffer, EC_TIMEOUTSTATE);
00122                                         printf("result %d.\n",j);
00123                                         printf("Request init state for slave %d\n", slave);
00124                                         ec_slave[slave].state = EC_STATE_INIT;
00125                                         ec_writestate(slave);
00126                                 }
00127                                 else
00128                                     printf("File not read OK.\n");
00129                         }
00130 
00131                 }
00132                 else
00133                 {
00134                         printf("No slaves found!\n");
00135                 }
00136                 printf("End firmware update example, close socket\n");
00137                 /* stop SOEM, close socket */
00138                 ec_close();
00139         }
00140         else
00141         {
00142                 printf("No socket connection on %s\nExcecute as root\n",ifname);
00143         }       
00144 }       
00145 
00146 int main(int argc, char *argv[])
00147 {
00148         printf("SOEM (Simple Open EtherCAT Master)\nFirmware update example\n");
00149 
00150         if (argc > 3)
00151         {               
00152                 argslave = atoi(argv[2]);
00153                 boottest(argv[1], argslave, argv[3]);
00154         }
00155         else
00156         {
00157                 printf("Usage: firm_update ifname1 slave fname\n");
00158                 printf("ifname = eth0 for example\n");
00159                 printf("slave = slave number in EtherCAT order 1..n\n");
00160                 printf("fname = binary file to store in slave\n");
00161                 printf("CAUTION! Using the wrong file can result in a bricked slave!\n");
00162         }       
00163         
00164         printf("End program\n");
00165         return (0);
00166 }


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