EthercatMasterWithThread.cpp
Go to the documentation of this file.
1 /****************************************************************
2  *
3  * Copyright (c) 2011
4  * All rights reserved.
5  *
6  * Hochschule Bonn-Rhein-Sieg
7  * University of Applied Sciences
8  * Computer Science Department
9  *
10  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
11  *
12  * Author:
13  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
14  * Supervised by:
15  * Gerhard K. Kraetzschmar
16  *
17  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
18  *
19  * This sofware is published under a dual-license: GNU Lesser General Public
20  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
21  * code may choose which terms they prefer.
22  *
23  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
24  *
25  * Redistribution and use in source and binary forms, with or without
26  * modification, are permitted provided that the following conditions are met:
27  *
28  * * Redistributions of source code must retain the above copyright
29  * notice, this list of conditions and the following disclaimer.
30  * * Redistributions in binary form must reproduce the above copyright
31  * notice, this list of conditions and the following disclaimer in the
32  * documentation and/or other materials provided with the distribution.
33  * * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
34  * contributors may be used to endorse or promote products derived from
35  * this software without specific prior written permission.
36  *
37  * This program is free software: you can redistribute it and/or modify
38  * it under the terms of the GNU Lesser General Public License LGPL as
39  * published by the Free Software Foundation, either version 2.1 of the
40  * License, or (at your option) any later version or the BSD license.
41  *
42  * This program is distributed in the hope that it will be useful,
43  * but WITHOUT ANY WARRANTY; without even the implied warranty of
44  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
45  * GNU Lesser General Public License LGPL and the BSD license for more details.
46  *
47  * You should have received a copy of the GNU Lesser General Public
48  * License LGPL and BSD license along with this program.
49  *
50  ****************************************************************/
51 extern "C" {
53 #include "nicdrv.h"
60 }
63 
64 namespace youbot {
65 
66 EthercatMasterWithThread::EthercatMasterWithThread(const std::string& configFile, const std::string& configFilePath) {
67  // Bouml preserved body begin 00041171
68 
69  this->ethercatConnectionEstablished = false;
70  ethernetDevice = "eth0";
71  timeTillNextEthercatUpdate = 1000; //usec
72  mailboxTimeout = 4000; //micro sec
73  ethercatTimeout = 500; //micro sec
76  stopThread = false;
77  this->automaticSendOn = true;
78  this->automaticReceiveOn = true;
79  this->configFileName = configFile;
80  this->configFilepath = configFilePath;
81  configfile = NULL;
82 
83  //initialize to zero
84  for (unsigned int i = 0; i < 4096; i++) {
85  IOmap_[i] = 0;
86  }
87  //read ethercat parameters form config file
89 
90  // configfile.setSection("EtherCAT");
91  configfile->readInto(ethernetDevice, "EtherCAT", "EthernetDevice");
92  configfile->readInto(timeTillNextEthercatUpdate, "EtherCAT", "EtherCATUpdateRate_[usec]");
93  configfile->readInto(ethercatTimeout, "EtherCAT", "EtherCATTimeout_[usec]");
94  configfile->readInto(mailboxTimeout, "EtherCAT", "MailboxTimeout_[usec]");
95  configfile->readInto(maxCommunicationErrors, "EtherCAT", "MaximumNumberOfEtherCATErrors");
96 
97  this->initializeEthercat();
98 
99 
100  // Bouml preserved body end 00041171
101 }
102 
104  // Bouml preserved body begin 000411F1
105  stopThread = true;
106  threads.join_all();
107  this->closeEthercat();
108  if (configfile != NULL)
109  delete configfile;
110  // Bouml preserved body end 000411F1
111 }
112 
114  // Bouml preserved body begin 000E6AF1
115  return true;
116  // Bouml preserved body end 000E6AF1
117 }
118 
121  // Bouml preserved body begin 00044A71
122  return this->nrOfSlaves;
123  // Bouml preserved body end 00044A71
124 }
125 
126 void EthercatMasterWithThread::AutomaticSendOn(const bool enableAutomaticSend) {
127  // Bouml preserved body begin 000775F1
128  this->automaticSendOn = enableAutomaticSend;
129 
130  if (this->automaticSendOn == true) {
131  unsigned int slaveNo = 0;
132 
133  for (unsigned int i = 0; i < automaticSendOffBufferVector.size(); i++) {
134  slaveNo = automaticSendOffBufferVector[i].jointNumber - 1;
135  slaveMessages[slaveNo].stctInput.Set(automaticSendOffBufferVector[i].stctInput);
136  slaveMessages[slaveNo].stctOutput.Set(automaticSendOffBufferVector[i].stctOutput);
137  slaveMessages[slaveNo].jointNumber.Set(automaticSendOffBufferVector[i].jointNumber);
138  }
139 
141  } else {
142  return;
143  }
144  return;
145  // Bouml preserved body end 000775F1
146 }
147 
148 void EthercatMasterWithThread::AutomaticReceiveOn(const bool enableAutomaticReceive) {
149  // Bouml preserved body begin 0008FB71
150  this->automaticReceiveOn = enableAutomaticReceive;
151 
152 
153  if (this->automaticReceiveOn == false) {
154 
155 
156  for (unsigned int i = 0; i < slaveMessages.size(); i++) {
157  slaveMessages[i].stctInput.Get(automaticReceiveOffBufferVector[i].stctInput);
158  slaveMessages[i].stctOutput.Get(automaticReceiveOffBufferVector[i].stctOutput);
159  slaveMessages[i].jointNumber.Get(automaticReceiveOffBufferVector[i].jointNumber);
160  }
161  }
162 
163  return;
164  // Bouml preserved body end 0008FB71
165 }
166 
169 void EthercatMasterWithThread::getEthercatDiagnosticInformation(std::vector<ec_slavet>& ethercatSlaveInfos) {
170  // Bouml preserved body begin 00061EF1
171  ethercatSlaveInfos = this->ethercatSlaveInfo;
172  for (unsigned int i = 0; i < ethercatSlaveInfos.size(); i++) {
173  ethercatSlaveInfos[i].inputs = NULL;
174  ethercatSlaveInfos[i].outputs = NULL;
175  }
176  // Bouml preserved body end 00061EF1
177 }
178 
182  // Bouml preserved body begin 000E68F1
183  throw std::runtime_error("When using the EthercatMaster with thread there is not need to send process data manual.");
184  return false;
185  // Bouml preserved body end 000E68F1
186 }
187 
191  // Bouml preserved body begin 000E6971
192  throw std::runtime_error("When using the EthercatMaster with thread there is not need to receive process data manual");
193  return false;
194  // Bouml preserved body end 000E6971
195 }
196 
200  // Bouml preserved body begin 000E69F1
201 
202  return ec_iserror();
203 
204  // Bouml preserved body end 000E69F1
205 }
206 
208  // Bouml preserved body begin 000EBCF1
209  {
210  boost::mutex::scoped_lock trajectoryControllerMutex(trajectoryControllerVectorMutex);
211  if (this->trajectoryControllers[JointNumber - 1] != NULL)
212  throw std::runtime_error("A joint trajectory controller is already register for this joint!");
213  if ((JointNumber - 1) >= this->trajectoryControllers.size())
214  throw std::out_of_range("Invalid joint number");
215 
216  this->trajectoryControllers[JointNumber - 1] = object;
217  }
218  LOG(debug) << "register joint trajectory controller for joint: " << JointNumber;
219  // Bouml preserved body end 000EBCF1
220 }
221 
223  // Bouml preserved body begin 000F06F1
224  {
225  boost::mutex::scoped_lock trajectoryControllerMutex(trajectoryControllerVectorMutex);
226  if ((JointNumber - 1) >= this->trajectoryControllers.size())
227  throw std::out_of_range("Invalid joint number");
228 
229  this->trajectoryControllers[JointNumber - 1] = NULL;
230  }
231  LOG(debug) << "delete joint trajectory controller registration for joint: " << JointNumber;
232  // Bouml preserved body end 000F06F1
233 }
234 
236  // Bouml preserved body begin 000F41F1
237 
238  return static_cast<unsigned int> (1.0 / ((double) timeTillNextEthercatUpdate / 1000 / 1000));
239  // Bouml preserved body end 000F41F1
240 }
241 
243  // Bouml preserved body begin 000F7771
244  return this->ethercatConnectionEstablished;
245  // Bouml preserved body end 000F7771
246 }
247 
248 void EthercatMasterWithThread::registerJointLimitMonitor(JointLimitMonitor* object, const unsigned int JointNumber) {
249  // Bouml preserved body begin 000FB071
250  {
251  boost::mutex::scoped_lock limitMonitorMutex(jointLimitMonitorVectorMutex);
252  if (this->jointLimitMonitors[JointNumber - 1] != NULL)
253  LOG(warning) << "A joint limit monitor is already register for this joint!";
254  if ((JointNumber - 1) >= this->jointLimitMonitors.size())
255  throw std::out_of_range("Invalid joint number");
256 
257  this->jointLimitMonitors[JointNumber - 1] = object;
258  }
259  LOG(debug) << "register a joint limit monitor for joint: " << JointNumber;
260  // Bouml preserved body end 000FB071
261 }
262 
263 void EthercatMasterWithThread::registerDataTrace(void* object, const unsigned int JointNumber) {
264  // Bouml preserved body begin 00105871
265  {
266  boost::mutex::scoped_lock datatraceM(dataTracesMutex);
267  if (this->dataTraces[JointNumber - 1] != NULL)
268  throw std::runtime_error("A data trace is already register for this joint!");
269  if ((JointNumber - 1) >= this->dataTraces.size())
270  throw std::out_of_range("Invalid joint number");
271 
272  this->dataTraces[JointNumber - 1] = (DataTrace*)object;
273  }
274  LOG(debug) << "register a data trace for joint: " << JointNumber;
275  // Bouml preserved body end 00105871
276 }
277 
278 void EthercatMasterWithThread::deleteDataTraceRegistration(const unsigned int JointNumber) {
279  // Bouml preserved body begin 001058F1
280  {
281  boost::mutex::scoped_lock datatraceM(dataTracesMutex);
282  if ((JointNumber - 1) >= this->dataTraces.size())
283  throw std::out_of_range("Invalid joint number");
284 
285  this->dataTraces[JointNumber - 1] = NULL;
286 
287  }
288  LOG(debug) << "removed data trace for joint: " << JointNumber;
289  // Bouml preserved body end 001058F1
290 }
291 
294  // Bouml preserved body begin 000410F1
295 
296  /* initialise SOEM, bind socket to ifname */
297  if (ec_init(const_cast<char*>(ethernetDevice.c_str()))) {
298  LOG(info) << "Initializing EtherCAT on " << ethernetDevice << " with communication thread";
299  /* find and auto-config slaves */
300  if (ec_config(TRUE, &IOmap_) > 0) {
301 
302  LOG(trace) << ec_slavecount << " EtherCAT slaves found and configured.";
303 
304  /* wait for all slaves to reach Pre OP state */
305  /*ec_statecheck(0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE);
306  if (ec_slave[0].state != EC_STATE_PRE_OP ){
307  LOG(debug) << "Not all slaves reached pre operational state.";
308  ec_readstate();
309  //If not all slaves operational find out which one
310  for(int i = 1; i<=ec_slavecount ; i++){
311  if(ec_slave[i].state != EC_STATE_PRE_OP){
312  printf("Slave %d State=%2x StatusCode=%4x : %s\n",
313  i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
314  }
315  }
316  }
317  */
318 
319  /* distributed clock is not working
320  //Configure distributed clock
321  if(!ec_configdc()){
322  LOG(warning) << "no distributed clock is available";
323  }else{
324 
325  uint32 CyclTime = 4000000;
326  uint32 CyclShift = 0;
327  for (int i = 1; i <= ec_slavecount; i++) {
328  ec_dcsync0(i, true, CyclTime, CyclShift);
329  }
330 
331  }
332  */
333 
334  /* wait for all slaves to reach SAFE_OP state */
335  ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
336  if (ec_slave[0].state != EC_STATE_SAFE_OP) {
337  LOG(warning) << "Not all EtherCAT slaves reached safe operational state.";
338  ec_readstate();
339  //If not all slaves operational find out which one
340  for (int i = 1; i <= ec_slavecount; i++) {
341  if (ec_slave[i].state != EC_STATE_SAFE_OP) {
342  LOG(info) << "Slave " << i << " State=" << ec_slave[i].state << " StatusCode=" << ec_slave[i].ALstatuscode << " : " << ec_ALstatuscode2string(ec_slave[i].ALstatuscode);
343 
344  }
345  }
346  }
347 
348 
349  //Read the state of all slaves
350  //ec_readstate();
351 
352  LOG(trace) << "Request operational state for all EtherCAT slaves";
353 
354  ec_slave[0].state = EC_STATE_OPERATIONAL;
355  // request OP state for all slaves
356  /* send one valid process data to make outputs in slaves happy*/
357  ec_send_processdata();
358  ec_receive_processdata(EC_TIMEOUTRET);
359  /* request OP state for all slaves */
360  ec_writestate(0);
361  // wait for all slaves to reach OP state
362 
363  ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
364  if (ec_slave[0].state == EC_STATE_OPERATIONAL) {
365  LOG(trace) << "Operational state reached for all EtherCAT slaves.";
366  } else {
367  throw std::runtime_error("Not all EtherCAT slaves reached operational state.");
368 
369  }
370 
371  } else {
372  throw std::runtime_error("No EtherCAT slaves found!");
373  }
374 
375  } else {
376  throw std::runtime_error("No socket connection on " + ethernetDevice + "\nExcecute as root");
377  }
378 
379 
380 
381  std::string baseJointControllerName = "TMCM-174";
382  std::string baseJointControllerNameAlternative = "TMCM-1632";
383  std::string manipulatorJointControllerName = "TMCM-174";
384  std::string ManipulatorJointControllerNameAlternative = "TMCM-1610";
385  std::string actualSlaveName;
386  nrOfSlaves = 0;
387  YouBotSlaveMsg emptySlaveMsg;
388  YouBotSlaveMsgThreadSafe emptySlaveMsgThreadSafe;
389 
390  configfile->readInto(baseJointControllerName, "BaseJointControllerName");
391  configfile->readInto(baseJointControllerNameAlternative, "BaseJointControllerNameAlternative");
392  configfile->readInto(manipulatorJointControllerName, "ManipulatorJointControllerName");
393  configfile->readInto(ManipulatorJointControllerNameAlternative, "ManipulatorJointControllerNameAlternative");
394 
395  //reserve memory for all slave with a input/output buffer
396  for (int cnt = 1; cnt <= ec_slavecount; cnt++) {
397  LOG(trace) << "Slave: " << cnt << " Name: " << ec_slave[cnt].name << " Output size: " << ec_slave[cnt].Obits
398  << "bits Input size: " << ec_slave[cnt].Ibits << "bits State: " << ec_slave[cnt].state
399  << " delay: " << ec_slave[cnt].pdelay; //<< " has dclock: " << (bool)ec_slave[cnt].hasdc;
400 
401  ethercatSlaveInfo.push_back(ec_slave[cnt]);
402 
403  actualSlaveName = ec_slave[cnt].name;
404  if ((actualSlaveName == baseJointControllerName || actualSlaveName == baseJointControllerNameAlternative ||
405  actualSlaveName == manipulatorJointControllerName || actualSlaveName == ManipulatorJointControllerNameAlternative
406  ) && ec_slave[cnt].Obits > 0 && ec_slave[cnt].Ibits > 0) {
407  nrOfSlaves++;
408  ethercatOutputBufferVector.push_back((SlaveMessageOutput*) (ec_slave[cnt].outputs));
409  ethercatInputBufferVector.push_back((SlaveMessageInput*) (ec_slave[cnt].inputs));
410  YouBotSlaveMailboxMsgThreadSafe emptyMailboxSlaveMsg(cnt);
411  mailboxMessages.push_back(emptyMailboxSlaveMsg);
412  pendingMailboxMsgsReply.push_back(false);
413  trajectoryControllers.push_back(NULL);
414  jointLimitMonitors.push_back(NULL);
415  slaveMessages.push_back(emptySlaveMsgThreadSafe);
416  outstandingMailboxMsgFlag.push_back(false);
417  newInputMailboxMsgFlag.push_back(false);
418  dataTraces.push_back(NULL);
419  }
420  }
422 
423  if (nrOfSlaves > 0) {
424  LOG(info) << nrOfSlaves << " EtherCAT slaves found";
425  } else {
426  throw std::runtime_error("No EtherCAT slave could be found");
427  return;
428  }
429 
430  stopThread = false;
431  threads.create_thread(boost::bind(&EthercatMasterWithThread::updateSensorActorValues, this));
432 
433  SLEEP_MILLISEC(10); //needed to start up thread and EtherCAT communication
434 
435  this->ethercatConnectionEstablished = true;
436  return;
437  // Bouml preserved body end 000410F1
438 }
439 
442  // Bouml preserved body begin 00041271
443 
444  this->ethercatConnectionEstablished = false;
445  // Request safe operational state for all slaves
446  ec_slave[0].state = EC_STATE_SAFE_OP;
447 
448  /* request SAFE_OP state for all slaves */
449  ec_writestate(0);
450 
451  //stop SOEM, close socket
452  ec_close();
453 
454  return true;
455  // Bouml preserved body end 00041271
456 }
457 
461 void EthercatMasterWithThread::setMsgBuffer(const YouBotSlaveMsg& msgBuffer, const unsigned int jointNumber) {
462  // Bouml preserved body begin 000414F1
463 
464  if (this->automaticSendOn == true) {
465  slaveMessages[jointNumber - 1].stctOutput.Set(msgBuffer.stctOutput);
466  } else {
467  YouBotSlaveMsg localMsg;
468  localMsg.stctInput = msgBuffer.stctInput;
469  localMsg.stctOutput = msgBuffer.stctOutput;
470  localMsg.jointNumber = jointNumber;
471  automaticSendOffBufferVector.push_back(localMsg);
472  }
473 
474  // Bouml preserved body end 000414F1
475 }
476 
480 void EthercatMasterWithThread::getMsgBuffer(const unsigned int jointNumber, YouBotSlaveMsg& returnMsg) {
481  // Bouml preserved body begin 00041571
482 
483  if (this->automaticReceiveOn == true) {
484  slaveMessages[jointNumber - 1].stctInput.Get(returnMsg.stctInput);
485  slaveMessages[jointNumber - 1].stctOutput.Get(returnMsg.stctOutput);
486  slaveMessages[jointNumber - 1].jointNumber.Get(returnMsg.jointNumber);
487  } else {
488  returnMsg = this->automaticReceiveOffBufferVector[jointNumber - 1];
489  }
490 
491  // Bouml preserved body end 00041571
492 }
493 
497 void EthercatMasterWithThread::setMailboxMsgBuffer(const YouBotSlaveMailboxMsg& msgBuffer, const unsigned int jointNumber) {
498  // Bouml preserved body begin 00049D71
499  this->mailboxMessages[jointNumber - 1].stctOutput.Set(msgBuffer.stctOutput);
500  outstandingMailboxMsgFlag[jointNumber - 1] = true;
501  return;
502  // Bouml preserved body end 00049D71
503 }
504 
508 bool EthercatMasterWithThread::getMailboxMsgBuffer(YouBotSlaveMailboxMsg& mailboxMsg, const unsigned int jointNumber) {
509  // Bouml preserved body begin 00049DF1
510  if (newInputMailboxMsgFlag[jointNumber - 1] == true) {
511  this->mailboxMessages[jointNumber - 1].stctInput.Get(mailboxMsg.stctInput);
512  newInputMailboxMsgFlag[jointNumber - 1] = false;
513  return true;
514  }
515  return false;
516  // Bouml preserved body end 00049DF1
517 }
518 
522  // Bouml preserved body begin 00052F71
523  // LOG(trace) << "send mailbox message (buffer two) slave " << mailboxMsg.getSlaveNo();
526  mailboxBufferSend[2] = mailboxMsg.stctOutput.typeNumber;
527  mailboxBufferSend[3] = mailboxMsg.stctOutput.motorNumber;
528  mailboxBufferSend[4] = mailboxMsg.stctOutput.value >> 24;
529  mailboxBufferSend[5] = mailboxMsg.stctOutput.value >> 16;
530  mailboxBufferSend[6] = mailboxMsg.stctOutput.value >> 8;
531  mailboxBufferSend[7] = mailboxMsg.stctOutput.value & 0xff;
532  if (ec_mbxsend(mailboxMsg.slaveNumber, &mailboxBufferSend, mailboxTimeout)) {
533  return true;
534  } else {
535  return false;
536  }
537  // Bouml preserved body end 00052F71
538 }
539 
543  // Bouml preserved body begin 00052FF1
544  if (ec_mbxreceive(mailboxMsg.slaveNumber, &mailboxBufferReceive, mailboxTimeout)) {
545  // LOG(trace) << "received mailbox message (buffer two) slave " << mailboxMsg.getSlaveNo();
546  mailboxMsg.stctInput.replyAddress = (int) mailboxBufferReceive[0];
547  mailboxMsg.stctInput.moduleAddress = (int) mailboxBufferReceive[1];
548  mailboxMsg.stctInput.status = (int) mailboxBufferReceive[2];
549  mailboxMsg.stctInput.commandNumber = (int) mailboxBufferReceive[3];
550  mailboxMsg.stctInput.value = (mailboxBufferReceive[4] << 24 | mailboxBufferReceive[5] << 16 | mailboxBufferReceive[6] << 8 | mailboxBufferReceive[7]);
551  return true;
552  }
553  return false;
554  // Bouml preserved body end 00052FF1
555 }
556 
560  // Bouml preserved body begin 0003F771
561 
562  long timeToWait = 0;
563  boost::posix_time::ptime startTime = boost::posix_time::microsec_clock::local_time();
564  boost::posix_time::time_duration pastTime;
565  // int counter = 0;
566  boost::posix_time::time_duration realperiode;
567  SlaveMessageOutput trajectoryContollerOutput;
568  YouBotSlaveMailboxMsg tempMsg;
569 
570 
571  while (!stopThread) {
572 
573  pastTime = boost::posix_time::microsec_clock::local_time() - startTime;
574  timeToWait = timeTillNextEthercatUpdate - pastTime.total_microseconds();
575 
576  if (timeToWait < 0 || timeToWait > (int) timeTillNextEthercatUpdate) {
577  // printf("Missed communication period of %d microseconds it have been %d microseconds \n",timeTillNextEthercatUpdate, (int)pastTime.total_microseconds()+ 100);
578  } else {
579  boost::this_thread::sleep(boost::posix_time::microseconds(timeToWait));
580  }
581 
582  // realperiode = boost::posix_time::microsec_clock::local_time() - startTime;
583  startTime = boost::posix_time::microsec_clock::local_time();
584 
585  /*
586  counter++;
587  timeSum = timeSum + realperiode;
588 
589  if(counter == 1000){
590 
591  double dtotaltime = (double)timeSum.total_microseconds()/counter;
592  printf("TotalTime %7.0lf us\n", dtotaltime);
593  counter = 0;
594  timeSum = startTime - startTime;
595  }
596  */
597 
598 
599 
600 
601  //send and receive data from ethercat
602  if (ec_send_processdata() == 0) {
603  LOG(warning) << "Sending process data failed";
604  }
605 
606  if (ec_receive_processdata(this->ethercatTimeout) == 0) {
607  if (communicationErrors == 0) {
608  LOG(warning) << "Receiving data failed";
609  }
611  } else {
613  }
614 
616  LOG(error) << "Lost EtherCAT connection";
617  this->closeEthercat();
618  stopThread = true;
619  break;
620  }
621 
622  if (ec_iserror())
623  LOG(warning) << "there is an error in the soem driver";
624 
625 
626  for (unsigned int i = 0; i < nrOfSlaves; i++) {
627 
628  //send data
629  if(automaticSendOn == true)
630  slaveMessages[i].stctOutput.Get(*(ethercatOutputBufferVector[i]));
631 
632  //receive data
633  if(automaticReceiveOn == true)
634  slaveMessages[i].stctInput.Set(*(ethercatInputBufferVector[i]));
635 
636 
637  // Limit checker
638  if (jointLimitMonitors[i] != NULL) {
639  this->jointLimitMonitors[i]->checkLimitsProcessData(*(ethercatInputBufferVector[i]), *(ethercatOutputBufferVector[i]));
640  }
641  // this->parseYouBotErrorFlags(secondBufferVector[i]);
642 
643  //send mailbox messages from first buffer
644  if (outstandingMailboxMsgFlag[i]) {
645  this->mailboxMessages[i].stctOutput.Get(tempMsg.stctOutput);
646  this->mailboxMessages[i].slaveNumber.Get(tempMsg.slaveNumber);
647  sendMailboxMessage(tempMsg);
648  outstandingMailboxMsgFlag[i] = false;
649  pendingMailboxMsgsReply[i] = true;
650  }
651 
652  //receive mailbox messages to first buffer
653  if (pendingMailboxMsgsReply[i]) {
654  this->mailboxMessages[i].slaveNumber.Get(tempMsg.slaveNumber);
655  if (receiveMailboxMessage(tempMsg)) {
656  this->mailboxMessages[i].stctInput.Set(tempMsg.stctInput);
657  newInputMailboxMsgFlag[i] = true;
658  pendingMailboxMsgsReply[i] = false;
659  }
660  }
661  }
662 
663  // Trajectory Controller
664  {
665  boost::mutex::scoped_lock trajectoryControllerMutex(trajectoryControllerVectorMutex);
666  for (unsigned int i = 0; i < nrOfSlaves; i++) {
667  if (this->trajectoryControllers[i] != NULL) {
668  if (this->trajectoryControllers[i]->updateTrajectoryController(*(ethercatInputBufferVector[i]), trajectoryContollerOutput)) {
669  // printf("send vel slave: %d", i);
670  (*(ethercatOutputBufferVector[i])).controllerMode = trajectoryContollerOutput.controllerMode;
671  (*(ethercatOutputBufferVector[i])).value = trajectoryContollerOutput.value;
672  //copy back
673  slaveMessages[i].stctOutput.Set(*(ethercatOutputBufferVector[i]));
674  }
675  }
676  }
677  }
678  // update Data Traces
679  for (unsigned int i = 0; i < nrOfSlaves; i++) {
680  {
681  boost::mutex::scoped_lock datatraceM(dataTracesMutex);
682  if (dataTraces[i] != NULL) {
683  ((DataTrace*)dataTraces[i])->updateTrace();
684  }
685  }
686  }
687  }
688  // Bouml preserved body end 0003F771
689 }
690 
692  // Bouml preserved body begin 000A9E71
693  std::stringstream errorMessageStream;
694  errorMessageStream << " ";
695  std::string errorMessage;
696  errorMessage = errorMessageStream.str();
697 
698 
699  if (messageBuffer.stctInput.errorFlags & OVER_CURRENT) {
700  LOG(error) << errorMessage << "got over current";
701  // throw JointErrorException(errorMessage + "got over current");
702  }
703 
704  if (messageBuffer.stctInput.errorFlags & UNDER_VOLTAGE) {
705  LOG(error) << errorMessage << "got under voltage";
706  // throw JointErrorException(errorMessage + "got under voltage");
707  }
708 
709  if (messageBuffer.stctInput.errorFlags & OVER_VOLTAGE) {
710  LOG(error) << errorMessage << "got over voltage";
711  // throw JointErrorException(errorMessage + "got over voltage");
712  }
713 
714  if (messageBuffer.stctInput.errorFlags & OVER_TEMPERATURE) {
715  LOG(error) << errorMessage << "got over temperature";
716  // throw JointErrorException(errorMessage + "got over temperature");
717  }
718 
719  if (messageBuffer.stctInput.errorFlags & MOTOR_HALTED) {
720  // LOG(info) << errorMessage << "is halted";
721  // throw JointErrorException(errorMessage + "is halted");
722  }
723 
724  if (messageBuffer.stctInput.errorFlags & HALL_SENSOR_ERROR) {
725  LOG(error) << errorMessage << "got hall sensor problem";
726  // throw JointErrorException(errorMessage + "got hall sensor problem");
727  }
728 
729  // if (messageBuffer.stctInput.errorFlags & ENCODER_ERROR) {
730  // LOG(error) << errorMessage << "got encoder problem";
731  // // throw JointErrorException(errorMessage + "got encoder problem");
732  // }
733  //
734  // if (messageBuffer.stctInput.errorFlags & INITIALIZATION_ERROR) {
735  // LOG(error) << errorMessage << "got inizialization problem";
736  // // throw JointErrorException(errorMessage + "got motor winding problem");
737  // }
738 
739 // if (messageBuffer.stctInput.errorFlags & PWM_MODE_ACTIVE) {
740  // LOG(error) << errorMessage << "has PWM mode active";
741  // throw JointErrorException(errorMessage + "the cycle time is violated");
742 // }
743 
744  if (messageBuffer.stctInput.errorFlags & VELOCITY_MODE) {
745  // LOG(info) << errorMessage << "has velocity mode active";
746  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
747  }
748 
749  if (messageBuffer.stctInput.errorFlags & POSITION_MODE) {
750  // LOG(info) << errorMessage << "has position mode active";
751  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
752  }
753 
754  if (messageBuffer.stctInput.errorFlags & TORQUE_MODE) {
755  // LOG(info) << errorMessage << "has torque mode active";
756  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
757  }
758 
759  // if (messageBuffer.stctInput.errorFlags & EMERGENCY_STOP) {
760  // LOG(info) << errorMessage << "has emergency stop active";
761  // // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
762  // }
763  //
764  // if (messageBuffer.stctInput.errorFlags & FREERUNNING) {
765  // // LOG(info) << errorMessage << "has freerunning active";
766  // // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
767  // }
768 
769  if (messageBuffer.stctInput.errorFlags & POSITION_REACHED) {
770  // LOG(info) << errorMessage << "has position reached";
771  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
772  }
773 
774  if (messageBuffer.stctInput.errorFlags & INITIALIZED) {
775  // LOG(info) << errorMessage << "is initialized";
776  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
777  }
778 
779  if (messageBuffer.stctInput.errorFlags & TIMEOUT) {
780  LOG(error) << errorMessage << "has a timeout";
781  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
782  }
783 
784  if (messageBuffer.stctInput.errorFlags & I2T_EXCEEDED) {
785  LOG(error) << errorMessage << "exceeded I2t";
786  // throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
787  }
788 
789  // Bouml preserved body end 000A9E71
790 }
791 
793 
795 
796 
797 } // namespace youbot
void AutomaticReceiveOn(const bool enableAutomaticReceive)
void setMailboxMsgBuffer(const YouBotSlaveMailboxMsg &msgBuffer, const unsigned int jointNumber)
Headerfile for ethercatdc.c.
void setMsgBuffer(const YouBotSlaveMsg &msgBuffer, const unsigned int jointNumber)
#define EC_TIMEOUTSTATE
Definition: ethercattype.h:102
std::vector< SlaveMessageInput * > ethercatInputBufferVector
Output part from the EtherCat message of the youBot EtherCat slaves.
bool getMailboxMsgBuffer(YouBotSlaveMailboxMsg &mailboxMsg, const unsigned int jointNumber)
std::vector< YouBotSlaveMailboxMsgThreadSafe > mailboxMessages
Reads and writes a configuration file.
Definition: ConfigFile.hpp:125
void deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber)
void registerJointTrajectoryController(JointTrajectoryController *object, const unsigned int JointNumber)
std::vector< YouBotSlaveMsgThreadSafe > slaveMessages
General typedefs and defines for EtherCAT.
std::vector< JointLimitMonitor * > jointLimitMonitors
Headerfile for ethercatcoe.c.
#define TRUE
Definition: osal.h:28
std::vector< SlaveMessageOutput * > ethercatOutputBufferVector
void getMsgBuffer(const unsigned int jointNumber, YouBotSlaveMsg &returnMsg)
void deleteDataTraceRegistration(const unsigned int JointNumber)
void initializeEthercat()
establishes the ethercat connection
bool receiveMailboxMessage(YouBotSlaveMailboxMsg &mailboxMsg)
#define LOG(level)
Definition: Logger.hpp:102
EthercatMasterWithThread(const std::string &configFile, const std::string &configFilePath)
bool sendMailboxMessage(const YouBotSlaveMailboxMsg &mailboxMsg)
bool readInto(T &var, const string &key) const
Definition: ConfigFile.hpp:317
It monitors the joint position and will decelerate and stop the joint if it is close the limits...
Creates a trace of all process data and reads all configuration parameter from one joint...
Definition: DataTrace.hpp:82
EtherCAT mailbox message of the youBot slaves (thread safe)
void registerDataTrace(void *object, const unsigned int JointNumber)
EtherCAT mailbox message of the youBot slaves.
SlaveMessageInput stctInput
void AutomaticSendOn(const bool enableAutomaticSend)
#define SLEEP_MILLISEC(millisec)
Definition: Time.hpp:60
#define EC_TIMEOUTRET
Definition: ethercattype.h:90
Input part from the EtherCat message of the youBot EtherCat slaves.
std::vector< JointTrajectoryController * > trajectoryControllers
Headerfile for ethercatbase.c.
std::vector< YouBotSlaveMsg > automaticReceiveOffBufferVector
void getEthercatDiagnosticInformation(std::vector< ec_slavet > &ethercatSlaveInfos)
SlaveMessageOutput stctOutput
Headerfile for ethercatmain.c.
void registerJointLimitMonitor(JointLimitMonitor *object, const unsigned int JointNumber)
EtherCat message of the youBot EtherCat slaves which is thread safe.
void parseYouBotErrorFlags(const YouBotSlaveMsg &messageBuffer)
EtherCat message of the youBot EtherCat slaves.
Headerfile for ethercatconfig.c.
bool closeEthercat()
closes the ethercat connection
std::vector< YouBotSlaveMsg > automaticSendOffBufferVector
unsigned int getNumberOfSlaves() const
return the quantity of ethercat slave which have an input/output buffer
Headerfile for ethercatprint.c.
char * ec_ALstatuscode2string(uint16 ALstatuscode)


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Jun 10 2019 15:46:24