00001 #ifndef YOUBOT_YOUBOTMANIPULATOR_H 00002 #define YOUBOT_YOUBOTMANIPULATOR_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 <youbot_driver/generic/Logger.hpp> 00058 #include <youbot_driver/generic/Units.hpp> 00059 #include <youbot_driver/generic/Time.hpp> 00060 #include <youbot_driver/generic/ConfigFile.hpp> 00061 #include <youbot_driver/generic/Exceptions.hpp> 00062 #include <youbot_driver/youbot/YouBotGripper.hpp> 00063 #include <youbot_driver/youbot/YouBotJoint.hpp> 00064 #include <youbot_driver/youbot/EthercatMaster.hpp> 00065 #include <youbot_driver/youbot/EthercatMasterInterface.hpp> 00066 #include <youbot_driver/youbot/EthercatMasterWithThread.hpp> 00067 #include <youbot_driver/youbot/EthercatMasterWithoutThread.hpp> 00068 #include <boost/ptr_container/ptr_vector.hpp> 00069 #include <boost/scoped_ptr.hpp> 00070 namespace youbot 00071 { 00072 00074 #define ARMJOINTS 5 00075 00076 00077 00078 class YouBotManipulator 00079 { 00080 public: 00081 YouBotManipulator(const std::string name, const std::string configFilePath); 00082 00083 virtual ~YouBotManipulator(); 00084 00086 void doJointCommutation(); 00087 00089 void calibrateManipulator(const bool forceCalibration = false); 00090 00091 void calibrateGripper(const bool forceCalibration = false); 00092 00095 YouBotJoint& getArmJoint(const unsigned int armJointNumber); 00096 00097 YouBotGripper& getArmGripper(); 00098 00102 virtual void setJointData(const std::vector<JointAngleSetpoint>& JointData); 00103 00107 virtual void getJointData(std::vector<JointSensedAngle>& data); 00108 00112 virtual void setJointData(const std::vector<JointVelocitySetpoint>& JointData); 00113 00117 virtual void getJointData(std::vector<JointSensedVelocity>& data); 00118 00122 virtual void setJointData(const std::vector<JointCurrentSetpoint>& JointData); 00123 00127 virtual void getJointData(std::vector<JointSensedCurrent>& data); 00128 00132 virtual void setJointData(const std::vector<JointTorqueSetpoint>& JointData); 00133 00137 virtual void getJointData(std::vector<JointSensedTorque>& data); 00138 00139 //whether the EtherCat connection is currently established 00140 bool isEtherCATConnectionEstablished(); 00141 00142 private: 00143 YouBotManipulator(const YouBotManipulator & source); 00144 00145 YouBotManipulator & operator=(const YouBotManipulator & source); 00146 00148 void commutationFirmware200(); 00149 00151 void commutationFirmware148(); 00152 00153 void initializeJoints(); 00154 00155 boost::scoped_ptr<ConfigFile> configfile; 00156 00157 boost::ptr_vector<YouBotJoint> joints; 00158 00159 boost::scoped_ptr<YouBotGripper> gripper; 00160 00161 int controllerType; 00162 00163 EthercatMasterInterface& ethercatMaster; 00164 00165 bool useGripper; 00166 00167 EthercatMasterWithThread* ethercatMasterWithThread; 00168 00169 int alternativeControllerType; 00170 00171 std::vector<std::string> supportedFirmwareVersions; 00172 00173 std::string actualFirmwareVersionAllJoints; 00174 00175 }; 00176 00177 } // namespace youbot 00178 #endif