OpenEtherCATsociety / SOEM

Simple Open Source EtherCAT Master
Other
1.24k stars 653 forks source link

SAFE_OP + ERROR after sending SDO #741

Closed open04 closed 9 months ago

open04 commented 9 months ago

Hi, first of all, thank you for making this library.

As the title stated, Im having SAFE_OP + ERROR after sending SDO. I modified the simple_test to try to rotate the motor. Here is the modified simple_test:

  `/** \file
  * \brief Example code for Simple Open EtherCAT master
  *
  * Usage : simple_test [ifname1]
  * ifname is NIC interface, f.e. eth0
  *
  * This is a minimal test.
  *
  * (c)Arthur Ketels 2010 - 2011
  */

  #include <stdio.h>
  #include <string.h>
  #include <inttypes.h>

  #include "ethercat.h"

  #define EC_TIMEOUTMON 500

  char IOmap[4096];
  OSAL_THREAD_HANDLE thread1;
  int expectedWKC;
  boolean needlf;
  volatile int wkc;
  boolean inOP;
  uint8 currentgroup = 0;

  typedef struct PACKED
  {
    int8_t modes_of_operation;
    uint16_t control_word;
    int32_t _position;
    int32_t _velocity;
    int16_t _torque;
  } output_pdo_t;

  typedef struct PACKED
  {
    int8_t modes_of_operation_display;
    uint16_t status_word;
    int32_t position_actual;
    int32_t velocity_actual;
    int16_t torque_actual;
  } input_pdo_t;

  input_pdo_t*input_pdo_;
  output_pdo_t*output_pdo_;

  void simpletest(char *ifname)
  {
      int oloop, iloop, chk;
      needlf = FALSE;
      inOP = FALSE;

     printf("Starting simple test\n");

     /* initialise SOEM, bind socket to ifname */
     if (ec_init(ifname))
     {
        printf("ec_init on %s succeeded.\n",ifname);
        /* find and auto-config slaves */

         if ( ec_config_init(FALSE) > 0 )
        {
           printf("%d slaves found and configured.\n",ec_slavecount);

           ec_config_map(&IOmap);

           ec_configdc();

           printf("Slaves mapped, state to SAFE_OP.\n");
           /* wait for all slaves to reach SAFE_OP state */
           ec_statecheck(0, EC_STATE_SAFE_OP,  EC_TIMEOUTSTATE * 4);

           oloop = ec_slave[0].Obytes;
           if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
           if (oloop > 8) oloop = 8;
           iloop = ec_slave[0].Ibytes;
           if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1;
           if (iloop > 8) iloop = 8;

           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]);

           printf("Request operational state for all slaves\n");
           expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
           printf("Calculated workcounter %d\n", expectedWKC);
           ec_slave[0].state = EC_STATE_OPERATIONAL;
           /* send one valid process data to make outputs in slaves happy*/
           ec_send_processdata();
           ec_receive_processdata(EC_TIMEOUTRET);
           /* request OP state for all slaves */
           ec_writestate(0);
           chk = 200;
           /* wait for all slaves to reach OP state */
           do
           {
              ec_send_processdata();
              ec_receive_processdata(EC_TIMEOUTRET);
              ec_statecheck(0, EC_STATE_OPERATIONAL, 50000);
           }
           while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));
           if (ec_slave[0].state == EC_STATE_OPERATIONAL )
           {
              printf("Operational state reached for all slaves.\n");
              inOP = TRUE;
              uint8_t val;

              output_pdo_ = (output_pdo_t*)ec_slave[0].outputs;
              input_pdo_ = (input_pdo_t*)ec_slave[0].inputs;

              val = 1;
              ec_SDOwrite(1, 0x2003, 03, FALSE, sizeof(val), &val,EC_TIMEOUTSAFE);
              printf("SDO write\n");
              osal_usleep(1000000);

              output_pdo_->modes_of_operation = 3;
              printf("MOO : %d\n", input_pdo_->modes_of_operation_display);
              osal_usleep(1000000);

              output_pdo_->control_word = 128;
              printf("CW128\n");
              osal_usleep(1000000);

              output_pdo_->control_word = 6;
              printf("CW6\n");
              osal_usleep(1000000);

              output_pdo_->control_word = 7;
              printf("CW7\n");
              osal_usleep(1000000);

              output_pdo_->control_word = 15;
              printf("CW15\n");
              osal_usleep(1000000);

                  /* cyclic loop */
              for(int i = 1; i <= 1000; i++)
              {
                 ec_send_processdata();
                 wkc = ec_receive_processdata(EC_TIMEOUTRET);

                      if(wkc >= expectedWKC)
                      {
                          printf("TV\n");
                          output_pdo_->_velocity = 500;
                      }
                      osal_usleep(5000);

                  }
                  inOP = FALSE;
              }
              else
              {
                  printf("Not all slaves reached operational state.\n");
                  ec_readstate();
                  for(int i = 1; i<=ec_slavecount ; i++)
                  {
                      if(ec_slave[i].state != EC_STATE_OPERATIONAL)
                      {
                          printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n",
                              i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
                      }
                  }
              }
              printf("\nRequest init state for all slaves\n");
              ec_slave[0].state = EC_STATE_INIT;
              /* request INIT state for all slaves */
              ec_writestate(0);
          }
          else
          {
              printf("No slaves found!\n");
          }
          printf("End simple test, close socket\n");
          /* stop SOEM, close socket */
          ec_close();
      }
      else
      {
          printf("No socket connection on %s\nExcecute as root\n",ifname);
      }
  }

  OSAL_THREAD_FUNC ecatcheck( void *ptr )
  {
      int slave;
      (void)ptr;                  /* Not used */

      while(1)
      {
          if( inOP && ((wkc < expectedWKC) || ec_group[currentgroup].docheckstate))
          {
              if (needlf)
              {
                 needlf = FALSE;
                 printf("\n");
              }
              /* one ore more slaves are not responding */
              ec_group[currentgroup].docheckstate = FALSE;
              ec_readstate();
              for (slave = 1; slave <= ec_slavecount; slave++)
              {
                 if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
                 {
                    ec_group[currentgroup].docheckstate = TRUE;
                    if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
                    {
                       printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
                       ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
                       ec_writestate(slave);
                    }
                    else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
                    {
                       printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
                       ec_slave[slave].state = EC_STATE_OPERATIONAL;
                       ec_writestate(slave);
                    }
                    else if(ec_slave[slave].state > EC_STATE_NONE)
                    {
                       if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
                       {
                          ec_slave[slave].islost = FALSE;
                          printf("MESSAGE : slave %d reconfigured\n",slave);
                       }
                    }
                    else if(!ec_slave[slave].islost)
                    {
                       /* re-check state */
                       ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
                       if (ec_slave[slave].state == EC_STATE_NONE)
                       {
                          ec_slave[slave].islost = TRUE;
                          printf("ERROR : slave %d lost\n",slave);
                       }
                    }
                 }
                 if (ec_slave[slave].islost)
                 {
                    if(ec_slave[slave].state == EC_STATE_NONE)
                    {
                       if (ec_recover_slave(slave, EC_TIMEOUTMON))
                       {
                          ec_slave[slave].islost = FALSE;
                          printf("MESSAGE : slave %d recovered\n",slave);
                       }
                    }
                    else
                    {
                       ec_slave[slave].islost = FALSE;
                       printf("MESSAGE : slave %d found\n",slave);
                    }
                 }
              }
              if(!ec_group[currentgroup].docheckstate)
                 printf("OK : all slaves resumed OPERATIONAL.\n");
          }
          osal_usleep(10000);
      }
  }

  int main(int argc, char *argv[])
  {
     printf("SOEM (Simple Open EtherCAT Master)\nSimple test\n");

     if (argc > 1)
     {
        /* create thread to handle slave error handling in OP */
  //      pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);
        osal_thread_create(&thread1, 128000, &ecatcheck, (void*) &ctime);
        /* start cyclic part */
        simpletest(argv[1]);
     }
     else
     {
        printf("Usage: simple_test ifname1\nifname = eth0 for example\n");
     }

     printf("End program\n");
     return (0);
  }`

there is no problem when I tried to run the original simple_test script. am I missing something?

open04 commented 9 months ago

Here is the log:

SOEM (Simple Open EtherCAT Master) Simple test Starting simple test ec_init on eth0 succeeded. 1 slaves found and configured. Slaves mapped, state to SAFE_OP. segments : 1 : 36 0 0 0 Request operational state for all slaves Calculated workcounter 3 Operational state reached for all slaves. SDO write ERROR : slave 1 is in SAFE_OP + ERROR, attempting ack. WARNING : slave 1 is in SAFE_OP, change to OPERATIONAL. MOO : 0 CW128 ERROR : slave 1 is in SAFE_OP + ERROR, attempting ack. WARNING : slave 1 is in SAFE_OP, change to OPERATIONAL. CW6 CW7 CW15

ArthurKetels commented 9 months ago

Yes the behaviour makes perfect sense. When a slave goes to operational a watchdog timer is started on the slave that monitors cyclic PDO transfers. After more than 100ms of no transfers the watchdog kicks in and the slave goes in safe-OP+error state.

You need to have a separate task that does continuous process-data transfers. See many posts here on how to do that (use the search function).

open04 commented 9 months ago

Hi Arthur, Thanks! Searched for the same issue here and I can now control my motor. Thanks again