25 #define mPi 3.14159265358979323846 30 #define KINLIB_VERSION_MAJOR 1 31 #define KINLIB_VERSION_MINOR 3 32 #define KINLIB_VERSION_REVISION 0 36 template<
typename _T>
inline _T
atan1(_T in1, _T in2) {
38 if(in1==0.0 && in2 == 0.0)
42 return (in2<0) ?
mPi*3.0/2.0 :
mPi/2.0;
45 return atan(in2/in1)+
mPi;
47 if( (in1>0.0) && (in2<0.0) )
48 return atan(in2/in1)+2.0*
mPi;
106 {0, 0, 0, 0, 0, -3.025529, 3.013311, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
107 0, 0, 0, 0,
mPi/2.0, -0.274889, 2.168572, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
108 0, 0, 0, 0.19, 0, -2.221804, 2.141519, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
109 0, 0, 0, 0.139, 0, -3.551745, 0.462512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
110 0, 0, 0.1473, 0, -
mPi/2.0, -4.546583, 1.422443, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
111 0, 0, 0.036, 0,
mPi/2.0, -2.085668, 3.656465, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
114 {0, 0, 0, 0, 0, -3.025529, 3.013311, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
115 0, 0, 0, 0,
mPi/2.0, -0.274889, 2.168572, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
116 0, 0, 0, 0.19, 0, -2.221804, 2.141519, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
117 0, 0, 0, 0.139, 0, -3.551745, 0.462512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
118 0, 0, 0.1473, 0, -
mPi/2.0, -4.546583, 1.422443, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
119 0,
mPi/2.0, 0.1505, 0,
mPi/2.0, -3.141593, 3.141593, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1};
122 {0, 0, 0, 0, 0, -3.025529, 3.013311, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
123 0, 0, 0, 0,
mPi/2.0, -0.274889, 2.168572, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
124 0, 0, 0, 0.19, 0, -2.221804, 2.141519, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
125 0, 0, 0, 0.139, 0, -3.551745, 0.462512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
126 0, 0, 0.1473+0.041, 0, -
mPi/2.0, -1.40499, 4.564036, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
129 {0, 0, 0, 0, 0, -3.025529, 3.013311, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
130 0, 0, 0, 0,
mPi/2.0, -0.274889, 2.168572, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
131 0, 0, 0, 0.19, 0, -2.221804, 2.141519, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
132 0, 0, 0, 0.139, 0, -3.551745, 0.462512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
133 0, 0, 0.1473, 0, -
mPi/2.0, -1.40499, 4.564036, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
134 0, 0, 0.036, 0,
mPi/2.0, -2.160718, 3.721042, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
137 {0, 0, 0, 0, 0, -3.025529, 3.013311, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
138 0, 0, 0, 0,
mPi/2.0, -0.274889, 2.168572, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
139 0, 0, 0, 0.19, 0, -2.221804, 2.141519, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
140 0, 0, 0, 0.139, 0, -3.551745, 0.462512, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
141 0, 0, 0.1473, 0, -
mPi/2.0, -1.40499, 4.564036, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
142 0,
mPi/2.0, 0.1505, 0,
mPi/2.0, -3.141593, 3.141593, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1};
225 int sign(
double value);
227 double round(
double x);
228 #endif // ifdef WIN32 235 std::vector<double>&
angle);
239 std::vector<double>&
angle);
241 double tol = 0.00001);
291 int setMDH(std::vector<double> theta, std::vector<double>
d,
292 std::vector<double>
a, std::vector<double>
alpha,
int typeNr = -1);
326 int setEPC(std::vector<int> epc);
336 int setEncOff(std::vector<int> encOffset);
358 int setAngOff(std::vector<double> angleOffset);
369 int setAngRan(std::vector<double> angleRange);
379 int setTcpOff(std::vector<double> tcpOffset);
426 int getMDH(std::vector<double>& theta, std::vector<double>&
d,
427 std::vector<double>&
a, std::vector<double>&
alpha);
440 int getEPC(std::vector<int>& epc);
447 int getEncOff(std::vector<int>& encOffset);
461 int getAngOff(std::vector<double>& angleOffset);
468 int getAngRan(std::vector<double>& angleRange);
475 int getAngStop(std::vector<double>& angleStop);
482 int getAngMin(std::vector<double>& angleMin);
489 int getAngMax(std::vector<double>& angleMax);
496 int getTcpOff(std::vector<double>& tcpOffset);
579 #endif //_KINEMATICS_H_
int _rotDir[MaxDof]
Rotation direction.
const double Link_length_90A_G[]
const double Link_length_180[]
const double Angle_range_90A_F[]
FloatVector FloatVector FloatVector int typeNr
Kinematics class using the kinematics lib.
const double Link_length_90B_G[]
const double Angle_range_180[]
int setEncOff(std::vector< int > encOffset)
This sets the encoder offsets.
int getImmob()
Get the immobile flag of the last joint.
const int Rotation_direction[]
Rotation direction.
const Real Katana6M90A_G_data[]
int setAngRan(std::vector< double > angleRange)
This sets the angle range.
Robots class definitions.
double _tcpOffset[4]
TCP offset.
int getAngStop(std::vector< double > &angleStop)
Get angle stop.
int rad2enc(std::vector< double > angles, std::vector< int > &encoders)
Converts angles to encoders.
const int Encoder_offset[]
Encoder offset.
int setRotDir(std::vector< int > rotDir)
This sets the rotation direction.
const double Angle_offset_90A_F[]
int getAngRan(std::vector< double > &angleRange)
Get the angle range.
const Real Katana6M90A_F_data[]
~KinematicsLib()
Destructor.
const double Angle_range_90B_G[]
const Real Katana6M90B_G_data[]
const double Link_length_90B_F[]
int getEncOff(std::vector< int > &encOffset)
Get the encoder offsets.
const int Encoder_per_cycle[]
Encoder per cycle.
int _dom
Degree of mobility.
double _angleMin[MaxDof]
Angle min.
bool _angRanInit
Angle range.
Base Class for the kinematics implementations.
int setMDH(std::vector< double > theta, std::vector< double > d, std::vector< double > a, std::vector< double > alpha, int typeNr=-1)
This sets the modified Denavit-Hartenberg parameters.
int invKin(std::vector< double > pose, std::vector< double > prev, std::vector< double > &angle)
int getAngOff(std::vector< double > &angleOffset)
Get the angle offsets.
int _encoderOffset[MaxDof]
Encoder offset.
int getDOF()
Get the degree of freedom.
const Real Katana6M90B_F_data[]
Modified DH notation robot class.
FloatVector FloatVector int maxBisection
int getDOM()
Get the degree of mobility.
const double Angle_range_90B_F[]
int anaGuess(std::vector< double > pose, std::vector< double > prev, std::vector< double > &angle)
int _epc[MaxDof]
Encoder per cycle.
int init()
This initializes the kinematics.
int getAngMin(std::vector< double > &angleMin)
Get angle min.
int invKin_bisec(std::vector< double > pose, std::vector< double > prev, std::vector< double > &conf, int maxBisection)
The usual rectangular matrix.
int setAngOff(std::vector< double > angleOffset)
This sets the angle offsets.
bool _matrixInit
Matrices for mDH, angle range and immobile data.
mRobot _robot
Roboop robot class.
const double Angle_offset_180[]
int _dof
Degree of freedom.
int mDH2K4DAng(std::vector< double > angleMDH, std::vector< double > &angleK4D)
This converts angles from mDH to Katana4D convention.
int getType()
Get the robot type.
FloatVector FloatVector * a
double _angleOffset[MaxDof]
const double Angle_offset_90B_F[]
bool checkConfig(std::vector< double > config, std::vector< double > pose, double tol=0.00001)
int setImmob(int immobile)
This sets the immobile flag of the last joint.
const double Angle_range_90A_G[]
bool _angOffInit
Angle offset.
double _angleRange[MaxDof]
const double LENGTH_MULTIPLIER
int getTcpOff(std::vector< double > &tcpOffset)
Get the tcp offset.
FloatVector FloatVector FloatVector * alpha
KinematicsLib()
Constructor.
int inverseKinematics(std::vector< double > pose, std::vector< double > prev, std::vector< double > &angles, int maxBisection=0)
Calculates the inverse kinematics.
int setLinkLen(std::vector< double > links)
This sets the link length parameters (part of mDH-parameters)
AnaGuess::Kinematics * _anaGuess
Analytical guess.
int getVersion(std::vector< int > &version)
Get the version number of the library.
bool _initialized
Kinematic initialized.
int setTcpOff(std::vector< double > tcpOffset)
This sets the tcp offset.
const Real Katana6M180_data[]
int getEPC(std::vector< int > &epc)
Get the encoders per cycle.
int K4D2mDHAng(std::vector< double > angleK4D, std::vector< double > &angleMDH)
This converts angles from Katana4D to mDH convention.
int directKinematics(std::vector< double > angles, std::vector< double > &pose)
Calculates the direct kinematics.
int getRotDir(std::vector< int > &rotDir)
Get the rotation direction.
int enc2rad(std::vector< int > encoders, std::vector< double > &angles)
Converts encoders to angles.
int angleArrMDH2vecK4D(const double arr[], std::vector< double > *vec)
int setType(int type)
This sets the robot type.
int _immobile
Last joint is immobile (eg. K_6M90A_G, K_6M90B_G), _dom = _dof - 1.
const double Angle_offset_90B_G[]
double _angleMax[MaxDof]
Angle max.
int getMaxDOF()
Get the maximum degree of freedom.
int getAngMax(std::vector< double > &angleMax)
Get angle max.
int setEPC(std::vector< int > epc)
This sets the encoders per cycle.
std::vector< int > encoders
double _linkLength[4]
Link length (for defined types)
const double Link_length_90A_F[]
const double Angle_offset_90A_G[]
int getMDH(std::vector< double > &theta, std::vector< double > &d, std::vector< double > &a, std::vector< double > &alpha)
Get the modified Denavit-Hartenberg parameters.