Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef _IKBASE_H_
00023 #define _IKBASE_H_
00024
00025
00026 #include "common/exception.h"
00027 #include "common/dllexport.h"
00028
00029 #include "KNI/kmlExt.h"
00030 #include "KNI/kmlCommon.h"
00031
00032 #include "KNI_InvKin/KatanaKinematics.h"
00033 #include "KNI_InvKin/KatanaKinematics6M90G.h"
00034 #include "KNI_InvKin/KatanaKinematics6M90T.h"
00035 #include "KNI_InvKin/KatanaKinematics6M180.h"
00036 #include "KNI_InvKin/KatanaKinematics5M180.h"
00037
00038 #include <vector>
00039 #include <memory>
00040 #include <cmath>
00041
00042
00043
00044 #ifndef TM_ENDLESS
00045 #define TM_ENDLESS -1 //!< timeout symbol for 'endless' waiting
00046 #endif
00047
00048
00049 class DLLDIR_IK CikBase : public CKatana {
00050
00051 private:
00052 std::unique_ptr<KNI::KatanaKinematics> _kinematicsImpl;
00053 bool _kinematicsIsInitialized;
00054 void _initKinematics();
00055
00056 public:
00057
00058 CikBase() : _kinematicsIsInitialized(false) { };
00059 ~CikBase();
00060
00065 void getKinematicsVersion(std::vector<int>& version);
00066
00072 void setTcpOffset(double xoff, double yoff, double zoff, double psioff);
00073
00076 void DKApos(double* position);
00077
00082 void getCoordinates(double& x, double& y, double& z, double& phi, double& theta, double& psi, bool refreshEncoders = true);
00083
00085 void getCoordinatesFromEncoders(std::vector<double>& pose, const std::vector<int>& encs);
00086
00090 void IKCalculate(double X,
00091 double Y,
00092 double Z,
00093 double Al,
00094 double Be,
00095 double Ga,
00096 std::vector<int>::iterator solution_iter);
00097
00101 void IKCalculate(double X,
00102 double Y,
00103 double Z,
00104 double Al,
00105 double Be,
00106 double Ga,
00107 std::vector<int>::iterator solution_iter,
00108 const std::vector<int>& actualPosition );
00109
00112 void IKGoto(double X,
00113 double Y,
00114 double Z,
00115 double Al,
00116 double Be,
00117 double Ga,
00118 bool wait = false,
00119 int tolerance = 100,
00120 long timeout = TM_ENDLESS);
00121
00124 void moveRobotTo(double x,
00125 double y,
00126 double z,
00127 double phi,
00128 double theta,
00129 double psi,
00130 bool waitUntilReached = false, int waitTimeout = TM_ENDLESS);
00131
00136 void moveRobotTo( std::vector<double> coordinates, bool waitUntilReached = false, int waitTimeout = TM_ENDLESS);
00137
00138 };
00139
00140
00141 #endif //_IKBASE_H_
00142