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 "generic/Logger.hpp" 00058 #include "generic/Units.hpp" 00059 #include "generic/Time.hpp" 00060 #include "generic/ConfigFile.hpp" 00061 #include "generic/Exceptions.hpp" 00062 #include "youbot/YouBotGripper.hpp" 00063 #include "youbot/YouBotJoint.hpp" 00064 #include "youbot/EthercatMaster.hpp" 00065 #include "youbot/EthercatMasterInterface.hpp" 00066 #include "youbot/EthercatMasterWithThread.hpp" 00067 #include "youbot/EthercatMasterWithoutThread.hpp" 00068 #include <boost/ptr_container/ptr_vector.hpp> 00069 #include <boost/scoped_ptr.hpp> 00070 namespace youbot { 00071 00072 /// The number of manipulator joints 00073 #define ARMJOINTS 5 00074 /////////////////////////////////////////////////////////////////////////////// 00075 /// It groups the manipulator joints and the gripper together 00076 /////////////////////////////////////////////////////////////////////////////// 00077 class YouBotManipulator { 00078 public: 00079 YouBotManipulator(const std::string name, const std::string configFilePath = "../config/"); 00080 00081 virtual ~YouBotManipulator(); 00082 00083 ///does the sine commutation of the arm joints 00084 void doJointCommutation(); 00085 00086 ///calibrate the reference position of the arm joints 00087 void calibrateManipulator(const bool forceCalibration = false); 00088 00089 void calibrateGripper(const bool forceCalibration = false); 00090 00091 ///return a joint form the arm1 00092 ///@param armJointNumber 1-5 for the arm joints 00093 YouBotJoint& getArmJoint(const unsigned int armJointNumber); 00094 00095 YouBotGripper& getArmGripper(); 00096 00097 ///commands positions or angles to all manipulator joints 00098 ///all positions will be set at the same time 00099 ///@param JointData the to command positions 00100 virtual void setJointData(const std::vector<JointAngleSetpoint>& JointData); 00101 00102 ///gets the position or angle of all manipulator joints which have been calculated from the actual encoder value 00103 ///These values are all read at the same time from the different joints 00104 ///@param data returns the angles by reference 00105 virtual void getJointData(std::vector<JointSensedAngle>& data); 00106 00107 ///commands velocities to all manipulator joints 00108 ///all velocities will be set at the same time 00109 ///@param JointData the to command velocities 00110 virtual void setJointData(const std::vector<JointVelocitySetpoint>& JointData); 00111 00112 ///gets the velocities of all manipulator joints which have been calculated from the actual encoder values 00113 ///These values are all read at the same time from the different joints 00114 ///@param data returns the velocities by reference 00115 virtual void getJointData(std::vector<JointSensedVelocity>& data); 00116 00117 ///commands current to all manipulator joints 00118 ///all current values will be set at the same time 00119 ///@param JointData the to command current 00120 virtual void setJointData(const std::vector<JointCurrentSetpoint>& JointData); 00121 00122 ///gets the motor currents of all manipulator joints which have been measured by a hal sensor 00123 ///These values are all read at the same time from the different joints 00124 ///@param data returns the actual motor currents by reference 00125 virtual void getJointData(std::vector<JointSensedCurrent>& data); 00126 00127 ///commands torque to all manipulator joints 00128 ///all torque values will be set at the same time 00129 ///@param JointData the to command torque 00130 virtual void setJointData(const std::vector<JointTorqueSetpoint>& JointData); 00131 00132 ///gets the joint torque of all manipulator joints which have been calculated from the current 00133 ///These values are all read at the same time from the different joints 00134 ///@param data returns the actual joint torque by reference 00135 virtual void getJointData(std::vector<JointSensedTorque>& data); 00136 00137 00138 private: 00139 YouBotManipulator(const YouBotManipulator & source); 00140 00141 YouBotManipulator & operator=(const YouBotManipulator & source); 00142 00143 ///does the commutation of the arm joints with firmware 2.0 00144 void commutationFirmware200(); 00145 00146 ///does the commutation of the arm joints with firmware 1.48 and below 00147 void commutationFirmware148(); 00148 00149 void initializeJoints(); 00150 00151 boost::scoped_ptr<ConfigFile> configfile; 00152 00153 boost::ptr_vector<YouBotJoint> joints; 00154 00155 boost::scoped_ptr<YouBotGripper> gripper; 00156 00157 int controllerType; 00158 00159 EthercatMasterInterface& ethercatMaster; 00160 00161 bool useGripper; 00162 00163 EthercatMasterWithThread* ethercatMasterWithThread; 00164 00165 int alternativeControllerType; 00166 00167 std::vector<std::string> supportedFirmwareVersions; 00168 00169 std::string actualFirmwareVersionAllJoints; 00170 00171 }; 00172 00173 } // namespace youbot 00174 #endif