OpenEtherCATsociety / SOEM

Simple Open Source EtherCAT Master
Other
1.31k stars 670 forks source link

Motor vibration and Sync loss #269

Closed dabhijeet closed 5 years ago

dabhijeet commented 5 years ago

Hi guys,

We are experimenting with SOEM on linux. After some changes in the redtest we are able to rotate the motor.

We are using Xenomai in our system. After testing the code we found that the sync is losing nearly after 1 day and even when we are rotating the motor using PID controller there is vibrations in movement.

We think that it maybe because the Network driver is not real time which is causing jitter. Maybe RTnet is required to get smooth motion with proper sync.

Please let us know what can be the cause of this problem.

Thanks in advance.

ArthurKetels commented 5 years ago

Ehhh, the is not a lot of information you are giving us. How should I know?

I have run lots and lots of systems with linux that keep sync for as long as you want. There could be issues with your hardware both on the master and slave side. Good instrumentation is very important in finding these kind of failures.

On the master side you can install latency triggers.

If you build the slave yourself then debugging there should be easy. Otherwise the slave often latches the sync fail reason and you can read it out to get a clue.

You could also swap master and/or slave system to see if it is something hardware or software specific.

What ind of slave controller are you running?

dabhijeet commented 5 years ago

We are using RTA stepping motor drives (4 ms Cycle time). There should not be any problem on slave side since it is a standard industrial drive and we have rotated the motor using TwinCAT and it was working properly without any vibration.

What kind of instrumentation (hardware) should we use to find the failures from master side?

Is Xenomai and RTnet necessary to get the proper sync without vibration?

If the Network driver is not real time will it cause jitter?

We are using Xenomai 3.0.7

ArthurKetels commented 5 years ago

First you could log a wireshark trace. It has timestamps that could give a clue about system or driver jitter. You can also use the ehtercat time that gets returned by soem after each PDO transfer. Compare that with the real time tread clock to see if there is excessive jitter or spikes.

For a 4ms system even standard linux would be enough (approx 500us jitter). Preempt-rt patch would make it very good (50us). No special need to go to xenomai and rtnet.

I have seen hardware however that has spikes over 10ms because of bios activity. No amount of RT system can cure that.

Again, instrument (can be software only) to get to the problem.

dabhijeet commented 5 years ago

Okay we will try wireshark for debugging.

In some websites we have seen that for best performance of EtherCAT, a portion of the CPU (i.e. if we have quad core then one core out of four) is dedicated for EtherCAT task only. Even sometimes if we have 2 or more RJ45 port then one port is dedicated for EtherCAT task.

How can we allocate one core and one RJ45 port for EtherCAT in linux.

dabhijeet commented 5 years ago

When we used Wireshark we got the following result.. Wireshark_normal_i5

  1. This is the result of Normal Linux (CPU i5)

Wireshark_normal_celeron_Xenomai

  1. This is the result of Xenomai (CPU celeron)

Wireshark_normal_i5_Xenomai

  1. This is the result of Xenomai (CPU i5)

Wireshark_industrial_motion_control

  1. This is the result of standard industrial motion controller (ARM)

Can we allocate one core and one RJ45 port for EtherCAT in linux? If we use Lubuntu or Ubuntu core will it reduce jitter? How can we achieve the graph result like the 4th one from xenomai?

ArthurKetels commented 5 years ago

It is a pity you did not post the complete wireshark capture. An averaged plot does not tell so much about packet to packet timing. It are often the small details that make or brake the solution.

Anyway, what bothers me that the linux packets/s is way off from the ARM comparison. I would expect the average pkt/s to be exactly the same (2000) for all platforms.

It is possible your PDO real time task has timing issues. Can you post that part of your code?

dabhijeet commented 5 years ago

#include "robot_ethercat_controller/ethercat_manager/ethercat_manager.h"

#include <unistd.h>
#include <stdio.h>
#include <time.h>

#include <boost/ref.hpp>
#include <boost/interprocess/sync/scoped_lock.hpp>
extern "C"{
#include <robot_ethercat_controller/ethercattype.h>
#include <robot_ethercat_controller/nicdrv.h>
#include <robot_ethercat_controller/ethercatbase.h>
#include <robot_ethercat_controller/ethercatmain.h>
#include <robot_ethercat_controller/ethercatdc.h>
#include <robot_ethercat_controller/ethercatcoe.h>
#include <robot_ethercat_controller/ethercatfoe.h>
#include <robot_ethercat_controller/ethercatconfig.h>
#include <robot_ethercat_controller/ethercatprint.h>
}

namespace 
{
static const unsigned cycletime = 4000000; // 4 ms
static const unsigned EC_TIMEOUTMON = 500;
static const int NSEC_PER_SECOND = 1e+9;

bool sync_flag = true; ///This hold the current status of EtherCat Sync

void timespecInc(struct timespec &tick, int nsec)
{
  tick.tv_nsec += nsec;
  while (tick.tv_nsec >= NSEC_PER_SECOND)
    {
      tick.tv_nsec -= NSEC_PER_SECOND;
      tick.tv_sec++;
    }
}

void handleErrors()
{
  // one ore more slaves are not responding 
  ec_group[0].docheckstate = FALSE;
  ec_readstate();

  // declaring argument of time() 
  time_t my_time = time(NULL); 

  for (int slave = 1; slave <= ec_slavecount; slave++)
  {
    if ((ec_slave[slave].group == 0) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
    {
      ec_group[0].docheckstate = TRUE;
      if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
      {

        sync_flag = false;

        fprintf(stderr, "ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
        // ctime() used to give the present time 
        printf("%s", ctime(&my_time)); 

        ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
        ec_writestate(slave);
      }
      else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
      {

        sync_flag = false;

        fprintf(stderr, "WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
        // ctime() used to give the present time 
        printf("%s", ctime(&my_time)); 

        ec_slave[slave].state = EC_STATE_OPERATIONAL;
        ec_writestate(slave);
      }
      else if(ec_slave[slave].state > 0)
      {
        if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
        {
          sync_flag = true;
          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_slave[slave].islost = TRUE;
          sync_flag = false;
          fprintf(stderr, "ERROR : slave %d lost\n",slave);
        }
      }
    }
    if (ec_slave[slave].islost)
    {
      if(!ec_slave[slave].state)
      {
        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);
      }
    }
  }
}

void cycleWorker(boost::mutex& mutex, bool& stop_flag)
{
  // 1ms in nanoseconds
  double period = cycletime;
  // get curren ttime
  struct timespec tick;
  clock_gettime(CLOCK_REALTIME, &tick);
  timespecInc(tick, period);

  while (!stop_flag) 
  {

    int expected_wkc = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
    int sent, wkc;
    {
      boost::mutex::scoped_lock lock(mutex);
      sent = ec_send_processdata();
      wkc = ec_receive_processdata(EC_TIMEOUTRET);
    }

    if (wkc < expected_wkc)
    {
      handleErrors();
    }

    // check overrun
    struct timespec before;
    clock_gettime(CLOCK_REALTIME, &before);
    double overrun_time = (before.tv_sec + double(before.tv_nsec)/NSEC_PER_SECOND) -  (tick.tv_sec + double(tick.tv_nsec)/NSEC_PER_SECOND);
    if (overrun_time > 0.0)
      {
    ;//fprintf(stderr, "  overrun: %f\n", overrun_time);
      }
    //usleep(THREAD_SLEEP_TIME);
    clock_nanosleep(CLOCK_REALTIME, TIMER_ABSTIME, &tick, NULL);
    timespecInc(tick, period);

  }
}

} // end of anonymous namespace

namespace ethercat {

////////////////////////////////////////////////////////////////////////////////////////////////
//Constructor
EtherCatManager::EtherCatManager(const std::string& ifname)
  : ifname_(ifname), 
    num_clients_(0),
    stop_flag_(false)
{

  if (initSoem(ifname)) 
  {

  // declaring argument of time() 
  time_t my_time = time(NULL); 

  // ctime() used to give the present time 
  fprintf(stderr,"Starting Time\n");  
  fprintf(stderr,"%s", ctime(&my_time));  

    cycle_thread_ = boost::thread(cycleWorker, 
                                  boost::ref(iomap_mutex_),
                                  boost::ref(stop_flag_));
  } 
  else 
 {
   // construction failed
   throw EtherCatError("Could not initialize SOEM");
 }

}

////////////////////////////////////////////////////////////////////////////////////////////////
//Destructor
EtherCatManager::~EtherCatManager()
{
  stop_flag_ = true;

  // Request init operational state for all slaves
  ec_slave[0].state = EC_STATE_INIT;

  /* request init state for all slaves */
  ec_writestate(0);

  //stop SOEM, close socket
  ec_close();
  cycle_thread_.join();
}

////////////////////////////////////////////////////////////////////////////////////////////////

//Init functions
bool EtherCatManager::initSoem(const std::string& ifname) 
{

  // Copy string contents because SOEM library doesn't 
  // practice const correctness
  const static unsigned MAX_BUFF_SIZE = 1024;
  char buffer[MAX_BUFF_SIZE];
  size_t name_size = ifname_.size();
  if (name_size > sizeof(buffer) - 1) 
  {
    fprintf(stderr, "Ifname %s exceeds maximum size of %u bytes\n", ifname_.c_str(), MAX_BUFF_SIZE);
    return false;
  }
  std::strncpy(buffer, ifname_.c_str(), MAX_BUFF_SIZE);

  printf("Initializing etherCAT master\n");

  if (!ec_init(buffer))
  {
    fprintf(stderr, "Could not initialize ethercat driver\n");
    return false;
  }

  /* find and auto-config slaves */
  if (ec_config_init(FALSE) <= 0)
  {
    fprintf(stderr, "No slaves found on %s\n", ifname_.c_str());
    return false;
  }

  printf("SOEM found and configured %d slaves\n\n", ec_slavecount);

  for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
  {

       int slave_manf = (int)ec_slave[cnt].eep_man;
       int slave_id = (int)ec_slave[cnt].eep_id;
       char *name = ec_slave[cnt].name;

       printf("Slave No: %d\n",cnt);
       printf("Name: %s\nMan: %8.8x ID: %8.8x\n\n",name,slave_manf, slave_id);

       if((slave_manf == 0x0000017f)) //Checking only the manf value
    {

            num_clients_++;

    }

   }  

  printf("Found %d Drivers\n", num_clients_);

//PRE-OPERATIONAL MODE
  //Checking all the slaves are pre-operational
  if (ec_statecheck(0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE*4) != EC_STATE_PRE_OP)
    {
      fprintf(stderr, "Could not set EC_STATE_PRE_OP\n");
      return false;
    }

//STATE IN BETWEEN PRE-OPERATION -> SAFE OPERATIONAL
  for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
  {

    try
    {

        int wc = 0; //work counter

    //Setting current ratio , SDO address=0x3201, Refer Pg.27
    uint8 cr=100;
    wc=ec_SDOwrite(cnt, 0x3201,0, FALSE, sizeof(cr), &cr, EC_TIMEOUTRXM);

        //Setting Revolution Direction.
        if((cnt==1)||(cnt==2)||(cnt==3))
        {uint8 rd=1;
        wc=ec_SDOwrite(cnt, 0x3212,0, FALSE, sizeof(rd), &rd, EC_TIMEOUTRXM);}
        else
        {uint8 rd=0;
        wc=ec_SDOwrite(cnt, 0x3212,0, FALSE, sizeof(rd), &rd, EC_TIMEOUTRXM);}

        if((cnt==1)||(cnt==2)||(cnt==3))
        {uint8 oc=7;
    wc=ec_SDOwrite(cnt, 0x320d, 0, FALSE, sizeof(oc), &oc, EC_TIMEOUTRXM);}
        else
        {uint8 oc=15;
    wc=ec_SDOwrite(cnt, 0x320d, 0, FALSE, sizeof(oc), &oc, EC_TIMEOUTRXM);}

        //Setting input config.
        if((cnt==1)||(cnt==2)||(cnt==3))
        {uint8 ic=14;
        wc=ec_SDOwrite(cnt, 0x320c, 0, FALSE, sizeof(ic), &ic, EC_TIMEOUTRXM);}
        else
        {uint8 ic=30;
        wc=ec_SDOwrite(cnt, 0x320c, 0, FALSE, sizeof(ic), &ic, EC_TIMEOUTRXM);}

    //Setting Following Error reaction code
    uint8 ferc=0;
    wc=ec_SDOwrite(cnt, 0x3206, 0, FALSE, sizeof(ferc), &ferc, EC_TIMEOUTRXM);
    uint8 ew=5;
    wc=ec_SDOwrite(cnt, 0x3205, 0, FALSE, sizeof(ew), &ew, EC_TIMEOUTRXM);

        //Setting Homing Method
    if((cnt==1)||(cnt==2))
        {int8 hm=3;
        wc=ec_SDOwrite(cnt, 0x6098, 0, FALSE, sizeof(hm), &hm, EC_TIMEOUTRXM);}
        else
        {int8 hm=4;
        wc=ec_SDOwrite(cnt, 0x6098, 0, FALSE, sizeof(hm), &hm, EC_TIMEOUTRXM);}

        if((cnt==1)||(cnt==3))
        {uint32 ss=3360;
        wc=ec_SDOwrite(cnt, 0x6099, 1, FALSE, sizeof(ss), &ss, EC_TIMEOUTRXM);}
        else if((cnt==4)||(cnt==5))
        {uint32 ss=3584;
        wc=ec_SDOwrite(cnt, 0x6099, 1, FALSE, sizeof(ss), &ss, EC_TIMEOUTRXM);}
        else
        {uint32 ss=3584;
        wc=ec_SDOwrite(cnt, 0x6099, 1, FALSE, sizeof(ss), &ss, EC_TIMEOUTRXM);}

        if((cnt==1)||(cnt==3))
        {uint32 sz=960;
        wc=ec_SDOwrite(cnt, 0x6099, 2, FALSE, sizeof(sz), &sz, EC_TIMEOUTRXM);}
        else if((cnt==4)||(cnt==5))
        {uint32 sz=1024;
        wc=ec_SDOwrite(cnt, 0x6099, 2, FALSE, sizeof(sz), &sz, EC_TIMEOUTRXM);}
        else
        {uint32 sz=1024;
        wc=ec_SDOwrite(cnt, 0x6099, 2, FALSE, sizeof(sz), &sz, EC_TIMEOUTRXM);}

        //Setting RPDO values
        /*int ret = 0;
        uint8 num_entries = 0;
        ret += ec_SDOwrite(cnt, 0x1700, 0x00, FALSE, sizeof(num_entries), &num_entries, EC_TIMEOUTRXM);
        uint32_t mapping;
        mapping = 0x60400010;
        ret += ec_SDOwrite(cnt, 0x1700, 0x01, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x60600008;
        ret += ec_SDOwrite(cnt, 0x1700, 0x02, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x00000008;
        ret += ec_SDOwrite(cnt, 0x1700, 0x03, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x607A0020;
        ret += ec_SDOwrite(cnt, 0x1700, 0x04, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        num_entries = 4;
        ret += ec_SDOwrite(cnt, 0x1700, 0x00, FALSE, sizeof(num_entries), &num_entries, EC_TIMEOUTRXM);

        //Setting TPDO values
        num_entries = 0;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x00, FALSE, sizeof(num_entries), &num_entries, EC_TIMEOUTRXM);
        mapping = 0x60410010;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x01, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x60610008;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x02, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x00000008;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x03, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x60640020;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x04, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        mapping = 0x603F0010;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x05, FALSE, sizeof(mapping), &mapping, EC_TIMEOUTRXM);
        num_entries = 5;
        ret += ec_SDOwrite(cnt, 0x1B00, 0x00, FALSE, sizeof(num_entries), &num_entries, EC_TIMEOUTRXM);    */         

    }
    catch(int e)
    {

        std::cout<<"Error in setting values during P-OP -> OP"<<std::endl;
        return false;

    }
  }

   printf("%d Total slaves Found and Configured.\n",ec_slavecount);

  // configure IOMap
  int iomap_size = ec_config_map(iomap_);
  printf("SOEM IOMap size: %d\n", iomap_size);

  /* configure DC options for every DC capable slave found in the list */
  ec_configdc();

  for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
  {

    try
    {

    uint32 ct=4000000; //Cycle time
    ec_FPWR(cnt, ECT_REG_DCCYCLE0, sizeof(ct), &ct, EC_TIMEOUTRET); /* SYNC0 cycle time */

    uint8 cuc=3;
    ec_FPWR(cnt, ECT_REG_DCSYNCACT, sizeof(cuc), &cuc, EC_TIMEOUTRET); /* activate cyclic operation */

        uint32 st=4000000;
        ec_SDOwrite(cnt, 0x1c32, 0xa, FALSE, sizeof(st), &st, EC_TIMEOUTRXM);
}
        catch(int e)
    {

        std::cout<<"Error in setting values during P-OP -> OP"<<std::endl;
        return false;

    }}

  // wait for all slaves to reach SAFE_OP state //
  //Note: If the program waits for sometime, it may be executing statecheck, it may take 3 to 4 sec to complete
  // '0' here addresses all slaves
  if (ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE*4) != EC_STATE_SAFE_OP)
   {
     fprintf(stderr, "Could not set EC_STATE_SAFE_OP\n");
     return false;
   }

  /* 
      This section attempts to bring all slaves to operational status. It does so
      by attempting to set the status of all slaves (ec_slave[0]) to operational,
      then proceeding through 40 send/recieve cycles each waiting up to 50 ms for a
      response about the status. 
  */
  ec_slave[0].state = EC_STATE_OPERATIONAL;
  ec_send_processdata();
  ec_receive_processdata(EC_TIMEOUTRET);

  ec_writestate(0);
  int chk = 40;
  do {
    ec_send_processdata();
    ec_receive_processdata(EC_TIMEOUTRET);
    ec_statecheck(0, EC_STATE_OPERATIONAL, 50000); // 50 ms wait for state check
  } while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));

  //Checking all slaves achieved operational states
  if(ec_statecheck(0,EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE) != EC_STATE_OPERATIONAL)
  {
    fprintf(stderr, "OPERATIONAL state not set, exiting\n");
    return false;
  }

  //Reading the current state of the slaves
  ec_readstate();

  //Printing the detailed parameters of all slaves
  for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
    {

      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",
         cnt, ec_slave[cnt].name, ec_slave[cnt].Obits, ec_slave[cnt].Ibits,
         ec_slave[cnt].state, ec_slave[cnt].pdelay, ec_slave[cnt].hasdc);
      if (ec_slave[cnt].hasdc) printf(" DCParentport:%d\n", ec_slave[cnt].parentport);
      printf(" Activeports:%d.%d.%d.%d\n", (ec_slave[cnt].activeports & 0x01) > 0 ,
         (ec_slave[cnt].activeports & 0x02) > 0 , 
         (ec_slave[cnt].activeports & 0x04) > 0 , 
         (ec_slave[cnt].activeports & 0x08) > 0 );
      printf(" Configured address: %4.4x\n", ec_slave[cnt].configadr);
    }

  //Printing the details of PDO of each slaves.
  //This will give a better idea of slaves during configuring
  for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
    {

      int ret = 0, l;
      uint16_t sync_mode;
      uint32_t cycle_time;
      uint32_t minimum_cycle_time;
      uint32_t sync0_cycle_time;
      l = sizeof(sync_mode);
      ret += ec_SDOread(cnt, 0x1c32, 0x01, FALSE, &l, &sync_mode, EC_TIMEOUTRXM);
      l = sizeof(cycle_time);
      ret += ec_SDOread(cnt, 0x1c32, 0x02, FALSE, &l, &cycle_time, EC_TIMEOUTRXM);
      l = sizeof(minimum_cycle_time);
      ret += ec_SDOread(cnt, 0x1c32, 0x05, FALSE, &l, &minimum_cycle_time, EC_TIMEOUTRXM);
      l = sizeof(sync0_cycle_time);
      ret += ec_SDOread(cnt, 0x1c32, 0x0a, FALSE, &l, &sync0_cycle_time, EC_TIMEOUTRXM);
      printf("PDO syncmode %02x, cycle time %d ns (min %d), sync0 cycle time %d ns, ret = %d\n", sync_mode, cycle_time, minimum_cycle_time, sync0_cycle_time, ret);
    }

/////////////////////////////////////////////////////////////////////////////////////////////////////////////

  printf("\nFinished configuration successfully\n");
  return true;

}

////////////////////////////////////////////////////////////////////////////////////////////////
//This function will return number of slaves detected by the master
int EtherCatManager::getNumClinets() const
{
  return num_clients_;
}

////////////////////////////////////////////////////////////////////////////////////////////////
bool EtherCatManager::getSyncStatus() const
{

    return sync_flag;

}

/////////////////////////////////////////////////////////////////////////////////////////////////
//Read the status of the specified slave
void EtherCatManager::getStatus(int slave_no, std::string &name, int &eep_man, int &eep_id, int &eep_rev, int &obits, int &ibits, int &state, int &pdelay, int &hasdc, int &activeports, int &configadr) const
{
  if (slave_no > ec_slavecount) {
    fprintf(stderr, "ERROR : slave_no(%d) is larger than ec_slavecount(%d)\n", slave_no, ec_slavecount);
    exit(1);
  }
  name = std::string(ec_slave[slave_no].name);
  eep_man = (int)ec_slave[slave_no].eep_man;
  eep_id  = (int)ec_slave[slave_no].eep_id;
  eep_rev = (int)ec_slave[slave_no].eep_rev;
  obits   = ec_slave[slave_no].Obits;
  ibits   = ec_slave[slave_no].Ibits;
  state   = ec_slave[slave_no].state;
  pdelay  = ec_slave[slave_no].pdelay;
  hasdc   = ec_slave[slave_no].hasdc;
  activeports = ec_slave[slave_no].activeports;
  configadr   = ec_slave[slave_no].configadr;
}

////////////////////////////////////////////////////////////////////////////////////////////////
//Write function to the ethercat slave
void EtherCatManager::write(int slave_no, uint8_t channel, uint8_t value)
{
  boost::mutex::scoped_lock lock(iomap_mutex_);
  ec_slave[slave_no].outputs[channel] = value;
}

void EtherCatManager::before_home()
{       for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
        {//Setting Interp_Enable Bit.

            uint8 ie=1;
            ec_SDOwrite(cnt, 0x3306,0, FALSE, sizeof(ie), &ie, EC_TIMEOUTRXM);

        }

}

void EtherCatManager::after_home()
{       

    for( int cnt = 1 ; cnt <= ec_slavecount ; cnt++)
        {
            //Setting Interp_Enable Bit.
            uint8 ie=0;
            ec_SDOwrite(cnt, 0x3306,0, FALSE, sizeof(ie), &ie, EC_TIMEOUTRXM);

    }

}

////////////////////////////////////////////////////////////////////////////////////////////////
//This will read the input channel of the slave

uint8_t EtherCatManager::readInput(int slave_no, uint8_t channel) const
{
  boost::mutex::scoped_lock lock(iomap_mutex_);
  if (slave_no > ec_slavecount) {
    fprintf(stderr, "ERROR : slave_no(%d) is larger than ec_slavecount(%d)\n", slave_no, ec_slavecount);
    exit(1);
  }
  if (channel*8 >= ec_slave[slave_no].Ibits) {
    fprintf(stderr, "ERROR : channel(%d) is larger than Input bits (%d)\n", channel*8, ec_slave[slave_no].Ibits);
    exit(1);
  }
  return ec_slave[slave_no].inputs[channel];
}
////////////////////////////////////////////////////////////////////////////////////////////////
//This will read the output channel from a specified slave
uint8_t EtherCatManager::readOutput(int slave_no, uint8_t channel) const
{
  boost::mutex::scoped_lock lock(iomap_mutex_);
  if (slave_no > ec_slavecount) {
    fprintf(stderr, "ERROR : slave_no(%d) is larger than ec_slavecount(%d)\n", slave_no, ec_slavecount);
    exit(1);
  }
  if (channel*8 >= ec_slave[slave_no].Obits) {
    fprintf(stderr, "ERROR : channel(%d) is larger than Output bits (%d)\n", channel*8, ec_slave[slave_no].Obits);
    exit(1);
  }
  return ec_slave[slave_no].outputs[channel];
}

/////////////////////////////////////////////////////////////////////////////////////////////////
//Function to write value to SD0 of a specified slave, the value can be any type
template <typename T>
uint8_t EtherCatManager::writeSDO(int slave_no, uint16_t index, uint8_t subidx, T value) const
{
  int ret;
  ret = ec_SDOwrite(slave_no, index, subidx, FALSE, sizeof(value), &value, EC_TIMEOUTSAFE);
  return ret;
}

/////////////////////////////////////////////////////////////////////////////////////////////////
template <typename T>
T EtherCatManager::readSDO(int slave_no, uint16_t index, uint8_t subidx) const
{
  int ret, l;
  T val;
  l = sizeof(val);
  ret = ec_SDOread(slave_no, index, subidx, FALSE, &l, &val, EC_TIMEOUTRXM);
  if ( ret <= 0 ) { // ret = Workcounter from last slave response
    fprintf(stderr, "Failed to read from ret:%d, slave_no:%d, index:0x%04x, subidx:0x%02x\n", ret, slave_no, index, subidx);
  }
  return val;
}
/////////////////////////////////////////////////////////////////////////////////////////////////

template uint8_t EtherCatManager::writeSDO<char> (int slave_no, uint16_t index, uint8_t subidx, char value) const;
template uint8_t EtherCatManager::writeSDO<int> (int slave_no, uint16_t index, uint8_t subidx, int value) const;
template uint8_t EtherCatManager::writeSDO<short> (int slave_no, uint16_t index, uint8_t subidx, short value) const;
template uint8_t EtherCatManager::writeSDO<long> (int slave_no, uint16_t index, uint8_t subidx, long value) const;
template uint8_t EtherCatManager::writeSDO<unsigned char> (int slave_no, uint16_t index, uint8_t subidx, unsigned char value) const;
template uint8_t EtherCatManager::writeSDO<unsigned int> (int slave_no, uint16_t index, uint8_t subidx, unsigned int value) const;
template uint8_t EtherCatManager::writeSDO<unsigned short> (int slave_no, uint16_t index, uint8_t subidx, unsigned short value) const;
template uint8_t EtherCatManager::writeSDO<unsigned long> (int slave_no, uint16_t index, uint8_t subidx, unsigned long value) const;

template char EtherCatManager::readSDO<char> (int slave_no, uint16_t index, uint8_t subidx) const;
template int EtherCatManager::readSDO<int> (int slave_no, uint16_t index, uint8_t subidx) const;
template short EtherCatManager::readSDO<short> (int slave_no, uint16_t index, uint8_t subidx) const;
template long EtherCatManager::readSDO<long> (int slave_no, uint16_t index, uint8_t subidx) const;
template unsigned char EtherCatManager::readSDO<unsigned char> (int slave_no, uint16_t index, uint8_t subidx) const;
template unsigned int EtherCatManager::readSDO<unsigned int> (int slave_no, uint16_t index, uint8_t subidx) const;
template unsigned short EtherCatManager::readSDO<unsigned short> (int slave_no, uint16_t index, uint8_t subidx) const;
template unsigned long EtherCatManager::readSDO<unsigned long> (int slave_no, uint16_t index, uint8_t subidx) const;

} //End of namespace
dabhijeet commented 5 years ago

Hi, I thought it is better to upload the whole code. Here, instead of using the single code we made an EtherCAT manager class and in its constructor we start the PDO thread.

ArthurKetels commented 5 years ago

Thanks for posting. Sorry to say, but there is quite a bit wrong in your code. For reference is is better to look at the SOEM red_test.c example.

a) The PDO exchange task should be running at real-time priority. All other tasks should be running at lower priority. In your code everything is running at the same (non-real-time?) priority.. b) There should be no mutexes in your PDO exchange task. In your code you use : boost::mutex::scoped_lock lock(mutex);. You either have to do all PDO handling in real-time context or you have to copy the PDO data with lock-less principles (triple-buffer, RCU, etc.). c) Confusingly you should not use CLOCK_REALTIME but CLOCK_MONOTONIC. Google the differences to understand why. d) handleErrors() should be run in non-real-time context. You can not call this from the PDO exchange task. Also try to rate limit the handleError() taks to 100Hz or so. Some use case might require better response time though. e) Not related to the code but please check the timing of the NIC driver you use. Many drivers have packet coalescing and interrupt mitigation as a default setting. See also drvcomment.txt.

Configuring slaves with SDO_write should be done with the special hook fucntion SOEM provides. Otherwise handleErrors() will not work in all conditions. Because a slave could reset and recovery is only possible by reconfiguring the slave. And SOEM should know how to do that.

Again, have a good look at the samples provided by SOEM. I believe most of your timing issues have more to do with your coding than internal hardware or OS issues.

dabhijeet commented 5 years ago

Thank you so much Sir, for taking the time to write the response. Now, we got a better idea of the issue. We will change our code as per redtest.c and then observe the results.

nakarlsson commented 5 years ago

Questions answered

dabhijeet commented 5 years ago

Regarding the vibration problem, we found out the issue. If we make the executable with the help of ROS. we can't do sudo rosrun ..... so in most of the websites they have given to use
sudo setcap cap_net_raw+ep
before running the ROS node. but if we do that then motor will run but it won't run smoothly. maybe some permission is missing. The best solution to this problem is to use sudo -s in the ROS terminal to elevate permissions to superuser After using this, ROS will run the motor smoothly.