EthercatMasterWithThread.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2011
00004  * All rights reserved.
00005  *
00006  * Hochschule Bonn-Rhein-Sieg
00007  * University of Applied Sciences
00008  * Computer Science Department
00009  *
00010  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00011  *
00012  * Author:
00013  * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov
00014  * Supervised by:
00015  * Gerhard K. Kraetzschmar
00016  *
00017  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00018  *
00019  * This sofware is published under a dual-license: GNU Lesser General Public 
00020  * License LGPL 2.1 and BSD license. The dual-license implies that users of this
00021  * code may choose which terms they prefer.
00022  *
00023  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00024  *
00025  * Redistribution and use in source and binary forms, with or without
00026  * modification, are permitted provided that the following conditions are met:
00027  *
00028  *     * Redistributions of source code must retain the above copyright
00029  *       notice, this list of conditions and the following disclaimer.
00030  *     * Redistributions in binary form must reproduce the above copyright
00031  *       notice, this list of conditions and the following disclaimer in the
00032  *       documentation and/or other materials provided with the distribution.
00033  *     * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its
00034  *       contributors may be used to endorse or promote products derived from
00035  *       this software without specific prior written permission.
00036  *
00037  * This program is free software: you can redistribute it and/or modify
00038  * it under the terms of the GNU Lesser General Public License LGPL as
00039  * published by the Free Software Foundation, either version 2.1 of the
00040  * License, or (at your option) any later version or the BSD license.
00041  *
00042  * This program is distributed in the hope that it will be useful,
00043  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00044  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00045  * GNU Lesser General Public License LGPL and the BSD license for more details.
00046  *
00047  * You should have received a copy of the GNU Lesser General Public
00048  * License LGPL and BSD license along with this program.
00049  *
00050  ****************************************************************/
00051 extern "C"
00052 {
00053 #include <youbot_driver/soem/ethercattype.h>
00054 #include <youbot_driver/soem/nicdrv.h>
00055 #include <youbot_driver/soem/ethercatbase.h>
00056 #include <youbot_driver/soem/ethercatmain.h>
00057 #include <youbot_driver/soem/ethercatconfig.h>
00058 #include <youbot_driver/soem/ethercatcoe.h>
00059 #include <youbot_driver/soem/ethercatdc.h>
00060 #include <youbot_driver/soem/ethercatprint.h>
00061 }
00062 #include <youbot_driver/youbot/EthercatMasterWithThread.hpp>
00063 #include <youbot_driver/youbot/DataTrace.hpp>
00064 
00065 namespace youbot
00066 {
00067 
00068 EthercatMasterWithThread::EthercatMasterWithThread(const std::string& configFile, const std::string& configFilePath)
00069 {
00070   // Bouml preserved body begin 00041171
00071 
00072   this->ethercatConnectionEstablished = false;
00073   ethernetDevice = "eth0";
00074   timeTillNextEthercatUpdate = 1000; //usec
00075   mailboxTimeout = 4000; //micro sec
00076   ethercatTimeout = 500; //micro sec
00077   communicationErrors = 0;
00078   maxCommunicationErrors = 100;
00079   stopThread = false;
00080   this->automaticSendOn = true;
00081   this->automaticReceiveOn = true;
00082   this->configFileName = configFile;
00083   this->configFilepath = configFilePath;
00084   configfile = NULL;
00085 
00086   //initialize to zero
00087   for (unsigned int i = 0; i < 4096; i++)
00088   {
00089     IOmap_[i] = 0;
00090   }
00091   //read ethercat parameters form config file
00092   configfile = new ConfigFile(this->configFileName, this->configFilepath);
00093 
00094   // configfile.setSection("EtherCAT");
00095   configfile->readInto(ethernetDevice, "EtherCAT", "EthernetDevice");
00096   configfile->readInto(timeTillNextEthercatUpdate, "EtherCAT", "EtherCATUpdateRate_[usec]");
00097   configfile->readInto(ethercatTimeout, "EtherCAT", "EtherCATTimeout_[usec]");
00098   configfile->readInto(mailboxTimeout, "EtherCAT", "MailboxTimeout_[usec]");
00099   configfile->readInto(maxCommunicationErrors, "EtherCAT", "MaximumNumberOfEtherCATErrors");
00100 
00101   this->initializeEthercat();
00102 
00103   // Bouml preserved body end 00041171
00104 }
00105 
00106 EthercatMasterWithThread::~EthercatMasterWithThread()
00107 {
00108   // Bouml preserved body begin 000411F1
00109   stopThread = true;
00110   threads.join_all();
00111   this->closeEthercat();
00112   if (configfile != NULL)
00113     delete configfile;
00114   // Bouml preserved body end 000411F1
00115 }
00116 
00117 bool EthercatMasterWithThread::isThreadActive()
00118 {
00119   // Bouml preserved body begin 000E6AF1
00120   return true;
00121   // Bouml preserved body end 000E6AF1
00122 }
00123 
00125 unsigned int EthercatMasterWithThread::getNumberOfSlaves() const
00126 {
00127   // Bouml preserved body begin 00044A71
00128   return this->nrOfSlaves;
00129   // Bouml preserved body end 00044A71
00130 }
00131 
00132 void EthercatMasterWithThread::AutomaticSendOn(const bool enableAutomaticSend)
00133 {
00134   // Bouml preserved body begin 000775F1
00135   this->automaticSendOn = enableAutomaticSend;
00136 
00137   if (this->automaticSendOn == true)
00138   {
00139     unsigned int slaveNo = 0;
00140 
00141     for (unsigned int i = 0; i < automaticSendOffBufferVector.size(); i++)
00142     {
00143       slaveNo = automaticSendOffBufferVector[i].jointNumber - 1;
00144       slaveMessages[slaveNo].stctInput.Set(automaticSendOffBufferVector[i].stctInput);
00145       slaveMessages[slaveNo].stctOutput.Set(automaticSendOffBufferVector[i].stctOutput);
00146       slaveMessages[slaveNo].jointNumber.Set(automaticSendOffBufferVector[i].jointNumber);
00147     }
00148 
00149     automaticSendOffBufferVector.clear();
00150   }
00151   else
00152   {
00153     return;
00154   }
00155   return;
00156   // Bouml preserved body end 000775F1
00157 }
00158 
00159 void EthercatMasterWithThread::AutomaticReceiveOn(const bool enableAutomaticReceive)
00160 {
00161   // Bouml preserved body begin 0008FB71
00162   this->automaticReceiveOn = enableAutomaticReceive;
00163 
00164   if (this->automaticReceiveOn == false)
00165   {
00166 
00167     for (unsigned int i = 0; i < slaveMessages.size(); i++)
00168     {
00169       slaveMessages[i].stctInput.Get(automaticReceiveOffBufferVector[i].stctInput);
00170       slaveMessages[i].stctOutput.Get(automaticReceiveOffBufferVector[i].stctOutput);
00171       slaveMessages[i].jointNumber.Get(automaticReceiveOffBufferVector[i].jointNumber);
00172     }
00173   }
00174 
00175   return;
00176   // Bouml preserved body end 0008FB71
00177 }
00178 
00181 void EthercatMasterWithThread::getEthercatDiagnosticInformation(std::vector<ec_slavet>& ethercatSlaveInfos)
00182 {
00183   // Bouml preserved body begin 00061EF1
00184   ethercatSlaveInfos = this->ethercatSlaveInfo;
00185   for (unsigned int i = 0; i < ethercatSlaveInfos.size(); i++)
00186   {
00187     ethercatSlaveInfos[i].inputs = NULL;
00188     ethercatSlaveInfos[i].outputs = NULL;
00189   }
00190   // Bouml preserved body end 00061EF1
00191 }
00192 
00195 bool EthercatMasterWithThread::sendProcessData()
00196 {
00197   // Bouml preserved body begin 000E68F1
00198   throw std::runtime_error("When using the EthercatMaster with thread there is not need to send process data manual.");
00199   return false;
00200   // Bouml preserved body end 000E68F1
00201 }
00202 
00205 bool EthercatMasterWithThread::receiveProcessData()
00206 {
00207   // Bouml preserved body begin 000E6971
00208   throw std::runtime_error(
00209       "When using the EthercatMaster with thread there is not need to receive process data manual");
00210   return false;
00211   // Bouml preserved body end 000E6971
00212 }
00213 
00216 bool EthercatMasterWithThread::isErrorInSoemDriver()
00217 {
00218   // Bouml preserved body begin 000E69F1
00219 
00220   return ec_iserror();
00221 
00222   // Bouml preserved body end 000E69F1
00223 }
00224 
00225 void EthercatMasterWithThread::registerJointTrajectoryController(JointTrajectoryController* object,
00226                                                                  const unsigned int JointNumber)
00227 {
00228   // Bouml preserved body begin 000EBCF1
00229   {
00230     boost::mutex::scoped_lock trajectoryControllerMutex(trajectoryControllerVectorMutex);
00231     if (this->trajectoryControllers[JointNumber - 1] != NULL)
00232       throw std::runtime_error("A joint trajectory controller is already register for this joint!");
00233     if ((JointNumber - 1) >= this->trajectoryControllers.size())
00234       throw std::out_of_range("Invalid joint number");
00235 
00236     this->trajectoryControllers[JointNumber - 1] = object;
00237   }
00238   LOG(debug) << "register joint trajectory controller for joint: " << JointNumber;
00239   // Bouml preserved body end 000EBCF1
00240 }
00241 
00242 void EthercatMasterWithThread::deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber)
00243 {
00244   // Bouml preserved body begin 000F06F1
00245   {
00246     boost::mutex::scoped_lock trajectoryControllerMutex(trajectoryControllerVectorMutex);
00247     if ((JointNumber - 1) >= this->trajectoryControllers.size())
00248       throw std::out_of_range("Invalid joint number");
00249 
00250     this->trajectoryControllers[JointNumber - 1] = NULL;
00251   }
00252   LOG(debug) << "delete joint trajectory controller registration for joint: " << JointNumber;
00253   // Bouml preserved body end 000F06F1
00254 }
00255 
00256 unsigned int EthercatMasterWithThread::getNumberOfThreadCyclesPerSecond()
00257 {
00258   // Bouml preserved body begin 000F41F1
00259 
00260   return static_cast<unsigned int>(1.0 / ((double)timeTillNextEthercatUpdate / 1000 / 1000));
00261   // Bouml preserved body end 000F41F1
00262 }
00263 
00264 bool EthercatMasterWithThread::isEtherCATConnectionEstablished()
00265 {
00266   // Bouml preserved body begin 000F7771
00267   return this->ethercatConnectionEstablished;
00268   // Bouml preserved body end 000F7771
00269 }
00270 
00271 void EthercatMasterWithThread::registerJointLimitMonitor(JointLimitMonitor* object, const unsigned int JointNumber)
00272 {
00273   // Bouml preserved body begin 000FB071
00274   {
00275     boost::mutex::scoped_lock limitMonitorMutex(jointLimitMonitorVectorMutex);
00276     if (this->jointLimitMonitors[JointNumber - 1] != NULL)
00277       LOG(warning) << "A joint limit monitor is already register for this joint!";
00278     if ((JointNumber - 1) >= this->jointLimitMonitors.size())
00279       throw std::out_of_range("Invalid joint number");
00280 
00281     this->jointLimitMonitors[JointNumber - 1] = object;
00282   }
00283   LOG(debug) << "register a joint limit monitor for joint: " << JointNumber;
00284   // Bouml preserved body end 000FB071
00285 }
00286 
00287 void EthercatMasterWithThread::registerDataTrace(void* object, const unsigned int JointNumber)
00288 {
00289   // Bouml preserved body begin 00105871
00290   {
00291     boost::mutex::scoped_lock datatraceM(dataTracesMutex);
00292     if (this->dataTraces[JointNumber - 1] != NULL)
00293       throw std::runtime_error("A data trace is already register for this joint!");
00294     if ((JointNumber - 1) >= this->dataTraces.size())
00295       throw std::out_of_range("Invalid joint number");
00296 
00297     this->dataTraces[JointNumber - 1] = (DataTrace*)object;
00298   }
00299   LOG(debug) << "register a data trace for joint: " << JointNumber;
00300   // Bouml preserved body end 00105871
00301 }
00302 
00303 void EthercatMasterWithThread::deleteDataTraceRegistration(const unsigned int JointNumber)
00304 {
00305   // Bouml preserved body begin 001058F1
00306   {
00307     boost::mutex::scoped_lock datatraceM(dataTracesMutex);
00308     if ((JointNumber - 1) >= this->dataTraces.size())
00309       throw std::out_of_range("Invalid joint number");
00310 
00311     this->dataTraces[JointNumber - 1] = NULL;
00312 
00313   }
00314   LOG(debug) << "removed data trace for joint: " << JointNumber;
00315   // Bouml preserved body end 001058F1
00316 }
00317 
00319 void EthercatMasterWithThread::initializeEthercat()
00320 {
00321   // Bouml preserved body begin 000410F1
00322 
00323   /* initialise SOEM, bind socket to ifname */
00324   if (ec_init(ethernetDevice.c_str()))
00325   {
00326     LOG(info) << "Initializing EtherCAT on " << ethernetDevice << " with communication thread";
00327     /* find and auto-config slaves */
00328     if (ec_config(TRUE, &IOmap_) > 0)
00329     {
00330 
00331       LOG(trace) << ec_slavecount << " EtherCAT slaves found and configured.";
00332 
00333       /* wait for all slaves to reach Pre OP state */
00334       /*ec_statecheck(0, EC_STATE_PRE_OP,  EC_TIMEOUTSTATE);
00335        if (ec_slave[0].state != EC_STATE_PRE_OP ){
00336        LOG(debug) << "Not all slaves reached pre operational state.";
00337        ec_readstate();
00338        //If not all slaves operational find out which one
00339        for(int i = 1; i<=ec_slavecount ; i++){
00340        if(ec_slave[i].state != EC_STATE_PRE_OP){
00341        printf("Slave %d State=%2x StatusCode=%4x : %s\n",
00342        i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
00343        }
00344        }
00345        }
00346        */
00347 
00348       /* distributed clock is not working
00349        //Configure distributed clock
00350        if(!ec_configdc()){
00351        LOG(warning) << "no distributed clock is available";
00352        }else{
00353 
00354        uint32 CyclTime = 4000000;
00355        uint32 CyclShift = 0;
00356        for (int i = 1; i <= ec_slavecount; i++) {
00357        ec_dcsync0(i, true, CyclTime, CyclShift);
00358        }
00359 
00360        }
00361        */
00362 
00363       /* wait for all slaves to reach SAFE_OP state */
00364       ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE);
00365       if (ec_slave[0].state != EC_STATE_SAFE_OP)
00366       {
00367         LOG(warning) << "Not all EtherCAT slaves reached safe operational state.";
00368         ec_readstate();
00369         //If not all slaves operational find out which one
00370         for (int i = 1; i <= ec_slavecount; i++)
00371         {
00372           if (ec_slave[i].state != EC_STATE_SAFE_OP)
00373           {
00374             LOG(info) << "Slave " << i << " State=" << ec_slave[i].state << " StatusCode=" << ec_slave[i].ALstatuscode
00375                 << " : " << ec_ALstatuscode2string(ec_slave[i].ALstatuscode);
00376 
00377           }
00378         }
00379       }
00380 
00381       //Read the state of all slaves
00382       //ec_readstate();
00383 
00384       LOG(trace) << "Request operational state for all EtherCAT slaves";
00385 
00386       ec_slave[0].state = EC_STATE_OPERATIONAL;
00387       // request OP state for all slaves
00388       /* send one valid process data to make outputs in slaves happy*/
00389       ec_send_processdata();
00390       ec_receive_processdata(EC_TIMEOUTRET);
00391       /* request OP state for all slaves */
00392       ec_writestate(0);
00393       // wait for all slaves to reach OP state
00394 
00395       ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
00396       if (ec_slave[0].state == EC_STATE_OPERATIONAL)
00397       {
00398         LOG(trace) << "Operational state reached for all EtherCAT slaves.";
00399       }
00400       else
00401       {
00402         throw std::runtime_error("Not all EtherCAT slaves reached operational state.");
00403 
00404       }
00405 
00406     }
00407     else
00408     {
00409       throw std::runtime_error("No EtherCAT slaves found!");
00410     }
00411 
00412   }
00413   else
00414   {
00415     throw std::runtime_error("No socket connection on " + ethernetDevice + "\nExcecute as root");
00416   }
00417 
00418   std::string baseJointControllerName = "TMCM-174";
00419   std::string baseJointControllerNameAlternative = "TMCM-1632";
00420   std::string manipulatorJointControllerName = "TMCM-174";
00421   std::string ManipulatorJointControllerNameAlternative = "TMCM-1610";
00422   std::string actualSlaveName;
00423   nrOfSlaves = 0;
00424   YouBotSlaveMsg emptySlaveMsg;
00425   YouBotSlaveMsgThreadSafe emptySlaveMsgThreadSafe;
00426 
00427   configfile->readInto(baseJointControllerName, "BaseJointControllerName");
00428   configfile->readInto(baseJointControllerNameAlternative, "BaseJointControllerNameAlternative");
00429   configfile->readInto(manipulatorJointControllerName, "ManipulatorJointControllerName");
00430   configfile->readInto(ManipulatorJointControllerNameAlternative, "ManipulatorJointControllerNameAlternative");
00431 
00432   //reserve memory for all slave with a input/output buffer
00433   for (int cnt = 1; cnt <= ec_slavecount; cnt++)
00434   {
00435     LOG(trace) << "Slave: " << cnt << " Name: " << ec_slave[cnt].name << " Output size: " << ec_slave[cnt].Obits
00436         << "bits Input size: " << ec_slave[cnt].Ibits << "bits State: " << ec_slave[cnt].state << " delay: "
00437         << ec_slave[cnt].pdelay; //<< " has dclock: " << (bool)ec_slave[cnt].hasdc;
00438 
00439     ethercatSlaveInfo.push_back(ec_slave[cnt]);
00440 
00441     actualSlaveName = ec_slave[cnt].name;
00442     if ((actualSlaveName == baseJointControllerName || actualSlaveName == baseJointControllerNameAlternative
00443         || actualSlaveName == manipulatorJointControllerName
00444         || actualSlaveName == ManipulatorJointControllerNameAlternative) && ec_slave[cnt].Obits > 0
00445         && ec_slave[cnt].Ibits > 0)
00446     {
00447       nrOfSlaves++;
00448       ethercatOutputBufferVector.push_back((SlaveMessageOutput*)(ec_slave[cnt].outputs));
00449       ethercatInputBufferVector.push_back((SlaveMessageInput*)(ec_slave[cnt].inputs));
00450       YouBotSlaveMailboxMsgThreadSafe emptyMailboxSlaveMsg(cnt);
00451       mailboxMessages.push_back(emptyMailboxSlaveMsg);
00452       pendingMailboxMsgsReply.push_back(false);
00453       trajectoryControllers.push_back(NULL);
00454       jointLimitMonitors.push_back(NULL);
00455       slaveMessages.push_back(emptySlaveMsgThreadSafe);
00456       outstandingMailboxMsgFlag.push_back(false);
00457       newInputMailboxMsgFlag.push_back(false);
00458       dataTraces.push_back(NULL);
00459     }
00460   }
00461   automaticReceiveOffBufferVector.reserve(slaveMessages.size());
00462 
00463   if (nrOfSlaves > 0)
00464   {
00465     LOG(info) << nrOfSlaves << " EtherCAT slaves found";
00466   }
00467   else
00468   {
00469     throw std::runtime_error("No EtherCAT slave could be found");
00470     return;
00471   }
00472 
00473   stopThread = false;
00474   threads.create_thread(boost::bind(&EthercatMasterWithThread::updateSensorActorValues, this));
00475 
00476   SLEEP_MILLISEC(10); //needed to start up thread and EtherCAT communication
00477 
00478   this->ethercatConnectionEstablished = true;
00479   return;
00480   // Bouml preserved body end 000410F1
00481 }
00482 
00484 bool EthercatMasterWithThread::closeEthercat()
00485 {
00486   // Bouml preserved body begin 00041271
00487 
00488   this->ethercatConnectionEstablished = false;
00489   // Request safe operational state for all slaves
00490   ec_slave[0].state = EC_STATE_SAFE_OP;
00491 
00492   /* request SAFE_OP state for all slaves */
00493   ec_writestate(0);
00494 
00495   //stop SOEM, close socket
00496   ec_close();
00497 
00498   return true;
00499   // Bouml preserved body end 00041271
00500 }
00501 
00505 void EthercatMasterWithThread::setMsgBuffer(const YouBotSlaveMsg& msgBuffer, const unsigned int jointNumber)
00506 {
00507   // Bouml preserved body begin 000414F1
00508 
00509   if (this->automaticSendOn == true)
00510   {
00511     slaveMessages[jointNumber - 1].stctOutput.Set(msgBuffer.stctOutput);
00512   }
00513   else
00514   {
00515     YouBotSlaveMsg localMsg;
00516     localMsg.stctInput = msgBuffer.stctInput;
00517     localMsg.stctOutput = msgBuffer.stctOutput;
00518     localMsg.jointNumber = jointNumber;
00519     automaticSendOffBufferVector.push_back(localMsg);
00520   }
00521 
00522   // Bouml preserved body end 000414F1
00523 }
00524 
00528 void EthercatMasterWithThread::getMsgBuffer(const unsigned int jointNumber, YouBotSlaveMsg& returnMsg)
00529 {
00530   // Bouml preserved body begin 00041571
00531 
00532   if (this->automaticReceiveOn == true)
00533   {
00534     slaveMessages[jointNumber - 1].stctInput.Get(returnMsg.stctInput);
00535     slaveMessages[jointNumber - 1].stctOutput.Get(returnMsg.stctOutput);
00536     slaveMessages[jointNumber - 1].jointNumber.Get(returnMsg.jointNumber);
00537   }
00538   else
00539   {
00540     returnMsg = this->automaticReceiveOffBufferVector[jointNumber - 1];
00541   }
00542 
00543   // Bouml preserved body end 00041571
00544 }
00545 
00549 void EthercatMasterWithThread::setMailboxMsgBuffer(const YouBotSlaveMailboxMsg& msgBuffer,
00550                                                    const unsigned int jointNumber)
00551 {
00552   // Bouml preserved body begin 00049D71
00553   this->mailboxMessages[jointNumber - 1].stctOutput.Set(msgBuffer.stctOutput);
00554   outstandingMailboxMsgFlag[jointNumber - 1] = true;
00555   return;
00556   // Bouml preserved body end 00049D71
00557 }
00558 
00562 bool EthercatMasterWithThread::getMailboxMsgBuffer(YouBotSlaveMailboxMsg& mailboxMsg, const unsigned int jointNumber)
00563 {
00564   // Bouml preserved body begin 00049DF1
00565   if (newInputMailboxMsgFlag[jointNumber - 1] == true)
00566   {
00567     this->mailboxMessages[jointNumber - 1].stctInput.Get(mailboxMsg.stctInput);
00568     newInputMailboxMsgFlag[jointNumber - 1] = false;
00569     return true;
00570   }
00571   return false;
00572   // Bouml preserved body end 00049DF1
00573 }
00574 
00577 bool EthercatMasterWithThread::sendMailboxMessage(const YouBotSlaveMailboxMsg& mailboxMsg)
00578 {
00579   // Bouml preserved body begin 00052F71
00580   //  LOG(trace) << "send mailbox message (buffer two) slave " << mailboxMsg.getSlaveNo();
00581   mailboxBufferSend[0] = mailboxMsg.stctOutput.moduleAddress;
00582   mailboxBufferSend[1] = mailboxMsg.stctOutput.commandNumber;
00583   mailboxBufferSend[2] = mailboxMsg.stctOutput.typeNumber;
00584   mailboxBufferSend[3] = mailboxMsg.stctOutput.motorNumber;
00585   mailboxBufferSend[4] = mailboxMsg.stctOutput.value >> 24;
00586   mailboxBufferSend[5] = mailboxMsg.stctOutput.value >> 16;
00587   mailboxBufferSend[6] = mailboxMsg.stctOutput.value >> 8;
00588   mailboxBufferSend[7] = mailboxMsg.stctOutput.value & 0xff;
00589   if (ec_mbxsend(mailboxMsg.slaveNumber, &mailboxBufferSend, mailboxTimeout))
00590   {
00591     return true;
00592   }
00593   else
00594   {
00595     return false;
00596   }
00597   // Bouml preserved body end 00052F71
00598 }
00599 
00602 bool EthercatMasterWithThread::receiveMailboxMessage(YouBotSlaveMailboxMsg& mailboxMsg)
00603 {
00604   // Bouml preserved body begin 00052FF1
00605   if (ec_mbxreceive(mailboxMsg.slaveNumber, &mailboxBufferReceive, mailboxTimeout))
00606   {
00607     //    LOG(trace) << "received mailbox message (buffer two) slave " << mailboxMsg.getSlaveNo();
00608     mailboxMsg.stctInput.replyAddress = (int)mailboxBufferReceive[0];
00609     mailboxMsg.stctInput.moduleAddress = (int)mailboxBufferReceive[1];
00610     mailboxMsg.stctInput.status = (int)mailboxBufferReceive[2];
00611     mailboxMsg.stctInput.commandNumber = (int)mailboxBufferReceive[3];
00612     mailboxMsg.stctInput.value = (mailboxBufferReceive[4] << 24 | mailboxBufferReceive[5] << 16
00613         | mailboxBufferReceive[6] << 8 | mailboxBufferReceive[7]);
00614     return true;
00615   }
00616   return false;
00617   // Bouml preserved body end 00052FF1
00618 }
00619 
00622 void EthercatMasterWithThread::updateSensorActorValues()
00623 {
00624   // Bouml preserved body begin 0003F771
00625 
00626   long timeToWait = 0;
00627   boost::posix_time::ptime startTime = boost::posix_time::microsec_clock::local_time();
00628   boost::posix_time::time_duration pastTime;
00629   //  int counter = 0;
00630   boost::posix_time::time_duration realperiode;
00631   //boost::posix_time::time_duration timeSum = startTime - startTime;
00632   SlaveMessageOutput trajectoryContollerOutput;
00633   YouBotSlaveMailboxMsg tempMsg;
00634 
00635   while (!stopThread)
00636   {
00637 
00638     pastTime = boost::posix_time::microsec_clock::local_time() - startTime;
00639     timeToWait = timeTillNextEthercatUpdate - pastTime.total_microseconds() - 100;
00640 
00641     if (timeToWait < 0 || timeToWait > (int)timeTillNextEthercatUpdate)
00642     {
00643       //    printf("Missed communication period of %d  microseconds it have been %d microseconds \n",timeTillNextEthercatUpdate, (int)pastTime.total_microseconds()+ 100);
00644     }
00645     else
00646     {
00647       boost::this_thread::sleep(boost::posix_time::microseconds(timeToWait));
00648     }
00649 
00650     // realperiode = boost::posix_time::microsec_clock::local_time() - startTime;
00651     startTime = boost::posix_time::microsec_clock::local_time();
00652 
00653     /*
00654      counter++;
00655      timeSum  = timeSum + realperiode;
00656 
00657      if(counter == 1000){
00658 
00659      double dtotaltime = (double)timeSum.total_microseconds()/counter;
00660      printf("TotalTime %7.0lf us\n", dtotaltime);
00661      counter = 0;
00662      timeSum = startTime - startTime;
00663      }
00664      */
00665 
00666     //send and receive data from ethercat
00667     if (ec_send_processdata() == 0)
00668     {
00669       LOG(warning) << "Sending process data failed";
00670     }
00671 
00672     if (ec_receive_processdata(this->ethercatTimeout) == 0)
00673     {
00674       if (communicationErrors == 0)
00675       {
00676         LOG(warning) << "Receiving data failed";
00677       }
00678       communicationErrors++;
00679     }
00680     else
00681     {
00682       communicationErrors = 0;
00683     }
00684 
00685 //after receiving too many consecutive communication errors, give up
00686     if (communicationErrors > maxCommunicationErrors)
00687     {
00688       LOG(error) << "Lost EtherCAT connection";
00689       this->closeEthercat();
00690       stopThread = true;
00691       break;
00692     }
00693 
00694     if (ec_iserror())
00695       LOG(warning) << "there is an error in the soem driver";
00696 
00697     for (unsigned int i = 0; i < nrOfSlaves; i++)
00698     {
00699 
00700       //send data
00701       if (automaticSendOn == true)
00702         slaveMessages[i].stctOutput.Get(*(ethercatOutputBufferVector[i]));
00703 
00704       //receive data
00705       if (automaticReceiveOn == true)
00706         slaveMessages[i].stctInput.Set(*(ethercatInputBufferVector[i]));
00707 
00708       // Limit checker
00709       if (jointLimitMonitors[i] != NULL)
00710       {
00711         this->jointLimitMonitors[i]->checkLimitsProcessData(*(ethercatInputBufferVector[i]),
00712                                                             *(ethercatOutputBufferVector[i]));
00713         //copy back changed velocity for limit checker
00714         slaveMessages[i].stctOutput.Set(*(ethercatOutputBufferVector[i]));
00715       }
00716       // this->parseYouBotErrorFlags(secondBufferVector[i]);
00717 
00718       //send mailbox messages from first buffer
00719       if (outstandingMailboxMsgFlag[i])
00720       {
00721         this->mailboxMessages[i].stctOutput.Get(tempMsg.stctOutput);
00722         this->mailboxMessages[i].slaveNumber.Get(tempMsg.slaveNumber);
00723         sendMailboxMessage(tempMsg);
00724         outstandingMailboxMsgFlag[i] = false;
00725         pendingMailboxMsgsReply[i] = true;
00726       }
00727 
00728       //receive mailbox messages to first buffer
00729       if (pendingMailboxMsgsReply[i])
00730       {
00731         this->mailboxMessages[i].slaveNumber.Get(tempMsg.slaveNumber);
00732         if (receiveMailboxMessage(tempMsg))
00733         {
00734           this->mailboxMessages[i].stctInput.Set(tempMsg.stctInput);
00735           newInputMailboxMsgFlag[i] = true;
00736           pendingMailboxMsgsReply[i] = false;
00737         }
00738       }
00739     }
00740 
00741     // Trajectory Controller
00742     {
00743       boost::mutex::scoped_lock trajectoryControllerMutex(trajectoryControllerVectorMutex);
00744       for (unsigned int i = 0; i < nrOfSlaves; i++)
00745       {
00746         if (this->trajectoryControllers[i] != NULL)
00747         {
00748           if (this->trajectoryControllers[i]->updateTrajectoryController(*(ethercatInputBufferVector[i]),
00749                                                                          trajectoryContollerOutput))
00750           {
00751             //   printf("send vel slave: %d", i);
00752             (*(ethercatOutputBufferVector[i])).controllerMode = trajectoryContollerOutput.controllerMode;
00753             (*(ethercatOutputBufferVector[i])).value = trajectoryContollerOutput.value;
00754             //copy back
00755             slaveMessages[i].stctOutput.Set(*(ethercatOutputBufferVector[i]));
00756           }
00757         }
00758       }
00759     }
00760     // update Data Traces
00761     for (unsigned int i = 0; i < nrOfSlaves; i++)
00762     {
00763       {
00764         boost::mutex::scoped_lock datatraceM(dataTracesMutex);
00765         if (dataTraces[i] != NULL)
00766         {
00767           ((DataTrace*)dataTraces[i])->updateTrace();
00768         }
00769       }
00770     }
00771   }
00772   // Bouml preserved body end 0003F771
00773 }
00774 
00775 void EthercatMasterWithThread::parseYouBotErrorFlags(const YouBotSlaveMsg& messageBuffer)
00776 {
00777   // Bouml preserved body begin 000A9E71
00778   std::stringstream errorMessageStream;
00779   errorMessageStream << " ";
00780   std::string errorMessage;
00781   errorMessage = errorMessageStream.str();
00782 
00783   if (messageBuffer.stctInput.errorFlags & OVER_CURRENT)
00784   {
00785     LOG(error) << errorMessage << "got over current";
00786     //    throw JointErrorException(errorMessage + "got over current");
00787   }
00788 
00789   if (messageBuffer.stctInput.errorFlags & UNDER_VOLTAGE)
00790   {
00791     LOG(error) << errorMessage << "got under voltage";
00792     //    throw JointErrorException(errorMessage + "got under voltage");
00793   }
00794 
00795   if (messageBuffer.stctInput.errorFlags & OVER_VOLTAGE)
00796   {
00797     LOG(error) << errorMessage << "got over voltage";
00798     //   throw JointErrorException(errorMessage + "got over voltage");
00799   }
00800 
00801   if (messageBuffer.stctInput.errorFlags & OVER_TEMPERATURE)
00802   {
00803     LOG(error) << errorMessage << "got over temperature";
00804     //   throw JointErrorException(errorMessage + "got over temperature");
00805   }
00806 
00807   if (messageBuffer.stctInput.errorFlags & MOTOR_HALTED)
00808   {
00809     //   LOG(info) << errorMessage << "is halted";
00810     //   throw JointErrorException(errorMessage + "is halted");
00811   }
00812 
00813   if (messageBuffer.stctInput.errorFlags & HALL_SENSOR_ERROR)
00814   {
00815     LOG(error) << errorMessage << "got hall sensor problem";
00816     //   throw JointErrorException(errorMessage + "got hall sensor problem");
00817   }
00818 
00819   //    if (messageBuffer.stctInput.errorFlags & ENCODER_ERROR) {
00820   //      LOG(error) << errorMessage << "got encoder problem";
00821   //      //   throw JointErrorException(errorMessage + "got encoder problem");
00822   //    }
00823   //
00824   //     if (messageBuffer.stctInput.errorFlags & INITIALIZATION_ERROR) {
00825   //      LOG(error) << errorMessage << "got inizialization problem";
00826   //      //   throw JointErrorException(errorMessage + "got motor winding problem");
00827   //    }
00828 
00829 //    if (messageBuffer.stctInput.errorFlags & PWM_MODE_ACTIVE) {
00830   //  LOG(error) << errorMessage << "has PWM mode active";
00831   //   throw JointErrorException(errorMessage + "the cycle time is violated");
00832 //    }
00833 
00834   if (messageBuffer.stctInput.errorFlags & VELOCITY_MODE)
00835   {
00836     //   LOG(info) << errorMessage << "has velocity mode active";
00837     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00838   }
00839 
00840   if (messageBuffer.stctInput.errorFlags & POSITION_MODE)
00841   {
00842     //   LOG(info) << errorMessage << "has position mode active";
00843     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00844   }
00845 
00846   if (messageBuffer.stctInput.errorFlags & TORQUE_MODE)
00847   {
00848     //   LOG(info) << errorMessage << "has torque mode active";
00849     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00850   }
00851 
00852   //    if (messageBuffer.stctInput.errorFlags & EMERGENCY_STOP) {
00853   //      LOG(info) << errorMessage << "has emergency stop active";
00854   //      //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00855   //    }
00856   //
00857   //    if (messageBuffer.stctInput.errorFlags & FREERUNNING) {
00858   //   //   LOG(info) << errorMessage << "has freerunning active";
00859   //      //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00860   //    }
00861 
00862   if (messageBuffer.stctInput.errorFlags & POSITION_REACHED)
00863   {
00864     //    LOG(info) << errorMessage << "has position reached";
00865     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00866   }
00867 
00868   if (messageBuffer.stctInput.errorFlags & INITIALIZED)
00869   {
00870     //  LOG(info) << errorMessage << "is initialized";
00871     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00872   }
00873 
00874   if (messageBuffer.stctInput.errorFlags & TIMEOUT)
00875   {
00876     LOG(error) << errorMessage << "has a timeout";
00877     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00878   }
00879 
00880   if (messageBuffer.stctInput.errorFlags & I2T_EXCEEDED)
00881   {
00882     LOG(error) << errorMessage << "exceeded I2t";
00883     //   throw JointErrorException(errorMessage + "need to initialize the sinus commutation");
00884   }
00885 
00886   // Bouml preserved body end 000A9E71
00887 }
00888 
00889 std::string EthercatMasterWithThread::configFileName;
00890 
00891 std::string EthercatMasterWithThread::configFilepath;
00892 
00893 } // namespace youbot


youbot_driver
Author(s): Jan Paulus
autogenerated on Mon Oct 6 2014 09:08:01