00001 #ifndef YOUBOT_ETHERCATMASTERWITHTHREAD_H 00002 #define YOUBOT_ETHERCATMASTERWITHTHREAD_H 00003 00004 /**************************************************************** 00005 * 00006 * Copyright (c) 2011 00007 * All rights reserved. 00008 * 00009 * Hochschule Bonn-Rhein-Sieg 00010 * University of Applied Sciences 00011 * Computer Science Department 00012 * 00013 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00014 * 00015 * Author: 00016 * Jan Paulus, Nico Hochgeschwender, Michael Reckhaus, Azamat Shakhimardanov 00017 * Supervised by: 00018 * Gerhard K. Kraetzschmar 00019 * 00020 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00021 * 00022 * This sofware is published under a dual-license: GNU Lesser General Public 00023 * License LGPL 2.1 and BSD license. The dual-license implies that users of this 00024 * code may choose which terms they prefer. 00025 * 00026 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00027 * 00028 * Redistribution and use in source and binary forms, with or without 00029 * modification, are permitted provided that the following conditions are met: 00030 * 00031 * * Redistributions of source code must retain the above copyright 00032 * notice, this list of conditions and the following disclaimer. 00033 * * Redistributions in binary form must reproduce the above copyright 00034 * notice, this list of conditions and the following disclaimer in the 00035 * documentation and/or other materials provided with the distribution. 00036 * * Neither the name of the Hochschule Bonn-Rhein-Sieg nor the names of its 00037 * contributors may be used to endorse or promote products derived from 00038 * this software without specific prior written permission. 00039 * 00040 * This program is free software: you can redistribute it and/or modify 00041 * it under the terms of the GNU Lesser General Public License LGPL as 00042 * published by the Free Software Foundation, either version 2.1 of the 00043 * License, or (at your option) any later version or the BSD license. 00044 * 00045 * This program is distributed in the hope that it will be useful, 00046 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00047 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00048 * GNU Lesser General Public License LGPL and the BSD license for more details. 00049 * 00050 * You should have received a copy of the GNU Lesser General Public 00051 * License LGPL and BSD license along with this program. 00052 * 00053 ****************************************************************/ 00054 #include <vector> 00055 #include <sstream> 00056 #include <string> 00057 #include <cstdio> 00058 #include <stdexcept> 00059 #include <iostream> 00060 #include <boost/thread.hpp> 00061 #include <boost/date_time/posix_time/posix_time.hpp> 00062 #include <youbot_driver/generic/dataobjectlockfree/DataObjectLockFree.hpp> 00063 #include <youbot_driver/generic/Logger.hpp> 00064 #include <youbot_driver/generic/Units.hpp> 00065 #include <youbot_driver/generic/Time.hpp> 00066 #include <youbot_driver/generic/Exceptions.hpp> 00067 #include <youbot_driver/generic/ConfigFile.hpp> 00068 #include <youbot_driver/youbot/ProtocolDefinitions.hpp> 00069 #include <youbot_driver/youbot/YouBotSlaveMsg.hpp> 00070 #include <youbot_driver/youbot/YouBotSlaveMailboxMsg.hpp> 00071 #include <youbot_driver/youbot/EthercatMaster.hpp> 00072 #include <youbot_driver/youbot/JointTrajectoryController.hpp> 00073 #include <youbot_driver/youbot/JointLimitMonitor.hpp> 00074 00075 extern "C" 00076 { 00077 #include <youbot_driver/soem/ethercattype.h> 00078 #include <youbot_driver/soem/ethercatmain.h> 00079 } 00080 00081 namespace youbot 00082 { 00083 00088 class EthercatMasterWithThread : public EthercatMasterInterface 00089 { 00090 friend class EthercatMaster; 00091 friend class YouBotJoint; 00092 friend class YouBotGripper; 00093 friend class YouBotGripperBar; 00094 private: 00095 EthercatMasterWithThread(const std::string& configFile, const std::string& configFilePath); 00096 00097 ~EthercatMasterWithThread(); 00098 00099 public: 00100 bool isThreadActive(); 00101 00103 unsigned int getNumberOfSlaves() const; 00104 00105 void AutomaticSendOn(const bool enableAutomaticSend); 00106 00107 void AutomaticReceiveOn(const bool enableAutomaticReceive); 00108 00111 void getEthercatDiagnosticInformation(std::vector<ec_slavet>& ethercatSlaveInfos); 00112 00115 bool sendProcessData(); 00116 00119 bool receiveProcessData(); 00120 00123 bool isErrorInSoemDriver(); 00124 00125 void registerJointTrajectoryController(JointTrajectoryController* object, const unsigned int JointNumber); 00126 00127 void deleteJointTrajectoryControllerRegistration(const unsigned int JointNumber); 00128 00129 unsigned int getNumberOfThreadCyclesPerSecond(); 00130 00131 bool isEtherCATConnectionEstablished(); 00132 00133 void registerJointLimitMonitor(JointLimitMonitor* object, const unsigned int JointNumber); 00134 00135 void registerDataTrace(void* object, const unsigned int JointNumber); 00136 00137 void deleteDataTraceRegistration(const unsigned int JointNumber); 00138 00139 private: 00141 void initializeEthercat(); 00142 00144 bool closeEthercat(); 00145 00149 void setMsgBuffer(const YouBotSlaveMsg& msgBuffer, const unsigned int jointNumber); 00150 00154 void getMsgBuffer(const unsigned int jointNumber, YouBotSlaveMsg& returnMsg); 00155 00159 void setMailboxMsgBuffer(const YouBotSlaveMailboxMsg& msgBuffer, const unsigned int jointNumber); 00160 00164 bool getMailboxMsgBuffer(YouBotSlaveMailboxMsg& mailboxMsg, const unsigned int jointNumber); 00165 00168 bool sendMailboxMessage(const YouBotSlaveMailboxMsg& mailboxMsg); 00169 00172 bool receiveMailboxMessage(YouBotSlaveMailboxMsg& mailboxMsg); 00173 00176 void updateSensorActorValues(); 00177 00178 void parseYouBotErrorFlags(const YouBotSlaveMsg& messageBuffer); 00179 00180 std::string ethernetDevice; 00181 00182 char IOmap_[4096]; 00183 00184 ec_mbxbuft mailboxBuffer; 00185 00186 unsigned int nrOfSlaves; 00187 00188 std::vector<SlaveMessageOutput*> ethercatOutputBufferVector; 00189 00190 std::vector<SlaveMessageInput*> ethercatInputBufferVector; 00191 00192 std::vector<YouBotSlaveMsgThreadSafe> slaveMessages; 00193 00194 std::vector<ec_slavet> ethercatSlaveInfo; 00195 00196 unsigned int ethercatTimeout; 00197 00198 //in microseconds 00199 unsigned int timeTillNextEthercatUpdate; 00200 00201 boost::thread_group threads; 00202 00203 volatile bool stopThread; 00204 00205 ec_mbxbuft mailboxBufferSend; 00206 00207 ec_mbxbuft mailboxBufferReceive; 00208 00209 std::vector<YouBotSlaveMsg> automaticSendOffBufferVector; 00210 00211 std::vector<YouBotSlaveMsg> automaticReceiveOffBufferVector; 00212 00213 std::vector<YouBotSlaveMailboxMsgThreadSafe> mailboxMessages; 00214 00215 unsigned int mailboxTimeout; 00216 00217 std::vector<bool> newInputMailboxMsgFlag; 00218 00219 std::vector<bool> outstandingMailboxMsgFlag; 00220 00221 std::vector<bool> pendingMailboxMsgsReply; 00222 00223 ConfigFile* configfile; 00224 00225 static std::string configFileName; 00226 00227 static std::string configFilepath; 00228 00229 bool automaticSendOn; 00230 00231 bool automaticReceiveOn; 00232 00233 bool ethercatConnectionEstablished; 00234 00235 long int communicationErrors; 00236 00237 long int maxCommunicationErrors; 00238 00239 std::vector<JointTrajectoryController*> trajectoryControllers; 00240 00241 boost::mutex trajectoryControllerVectorMutex; 00242 00243 std::vector<JointLimitMonitor*> jointLimitMonitors; 00244 00245 boost::mutex jointLimitMonitorVectorMutex; 00246 00247 std::vector<void*> dataTraces; 00248 00249 boost::mutex dataTracesMutex; 00250 00251 }; 00252 00253 } // namespace youbot 00254 #endif