00001 /*************************************************************************** 00002 * Copyright (c) Jürgen Riegel (juergen.riegel@web.de) 2002 * 00003 * * 00004 * This file is part of the FreeCAD CAx development system. * 00005 * * 00006 * This library is free software; you can redistribute it and/or * 00007 * modify it under the terms of the GNU Library General Public * 00008 * License as published by the Free Software Foundation; either * 00009 * version 2 of the License, or (at your option) any later version. * 00010 * * 00011 * This library is distributed in the hope that it will be useful, * 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of * 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * 00014 * GNU Library General Public License for more details. * 00015 * * 00016 * You should have received a copy of the GNU Library General Public * 00017 * License along with this library; see the file COPYING.LIB. If not, * 00018 * write to the Free Software Foundation, Inc., 59 Temple Place, * 00019 * Suite 330, Boston, MA 02111-1307, USA * 00020 * * 00021 ***************************************************************************/ 00022 00023 00024 #ifndef ROBOT_ROBOT6AXLE_H 00025 #define ROBOT_ROBOT6AXLE_H 00026 00027 #include "kdl_cp/chain.hpp" 00028 #include "kdl_cp/jntarray.hpp" 00029 00030 #include <Base/Persistence.h> 00031 #include <Base/Placement.h> 00032 00033 namespace Robot 00034 { 00035 00037 struct AxisDefinition { 00038 double a; // a of the Denavit-Hartenberg parameters (mm) 00039 double alpha; // alpha of the Denavit-Hartenberg parameters (°) 00040 double d; // d of the Denavit-Hartenberg parameters (mm) 00041 double theta; // a of the Denavit-Hartenberg parameters (°) 00042 double rotDir; // rotational direction (1|-1) 00043 double maxAngle; // soft ends + in ° 00044 double minAngle; // soft ends - in ° 00045 double velocity; // max vlocity of the axle in °/s 00046 }; 00047 00048 00051 class RobotExport Robot6Axis : public Base::Persistence 00052 { 00053 TYPESYSTEM_HEADER(); 00054 00055 public: 00056 Robot6Axis(); 00057 ~Robot6Axis(); 00058 00059 // from base class 00060 virtual unsigned int getMemSize (void) const; 00061 virtual void Save (Base::Writer &/*writer*/) const; 00062 virtual void Restore(Base::XMLReader &/*reader*/); 00063 00064 // interface 00066 void setKinematic(const AxisDefinition KinDef[6]); 00068 void readKinematic(const char * FileName); 00069 00071 bool setTo(const Base::Placement &To); 00072 bool setAxis(int Axis,double Value); 00073 double getAxis(int Axis); 00074 double getMaxAngle(int Axis); 00075 double getMinAngle(int Axis); 00077 bool calcTcp(void); 00078 Base::Placement getTcp(void); 00079 00080 //void setKinematik(const std::vector<std::vector<float> > &KinTable); 00081 00082 00083 protected: 00084 KDL::Chain Kinematic; 00085 KDL::JntArray Actuall; 00086 KDL::JntArray Min; 00087 KDL::JntArray Max; 00088 KDL::Frame Tcp; 00089 00090 double Velocity[6]; 00091 double RotDir [6]; 00092 00093 }; 00094 00095 } //namespace Part 00096 00097 00098 #endif // PART_TOPOSHAPE_H