kinematics.h
Go to the documentation of this file.
1 /**************************************************************************
2 * kinematics.h -
3 * Kinematics Interface kinematics class for Katana4XX
4 * Copyright (C) 2007-2008 Neuronics AG
5 * PKE/UKE 2007, JHA 2008
6 **************************************************************************/
7 #ifndef _KINEMATICS_H_
8 #define _KINEMATICS_H_
9 
10 
11 #include "roboop/source/robot.h"
12 #include "roboop/source/utils.h"
14 
18 
19 #include "katana_common.h"
20 
21 #include <vector>
22 #include <string>
23 
24 
25 #define mPi 3.14159265358979323846
26 
27 #define EDOM 33
28 #define ERANGE 34
29 
30 #define KINLIB_VERSION_MAJOR 1
31 #define KINLIB_VERSION_MINOR 3
32 #define KINLIB_VERSION_REVISION 0
33 
35 
36 template<typename _T> inline _T atan1(_T in1, _T in2) {
37 
38  if(in1==0.0 && in2 == 0.0)
39  return 0.0;
40 
41  if(in1==0.0)
42  return (in2<0) ? mPi*3.0/2.0 : mPi/2.0;
43 
44  if(in1<0.0)
45  return atan(in2/in1)+mPi;
46 
47  if( (in1>0.0) && (in2<0.0) )
48  return atan(in2/in1)+2.0*mPi;
49 
50  return atan(in2/in1);
51 }
52 
54 
56 K_6M90A_F=0, // Katana 6M90A with Flange
57 K_6M90A_G=1, // Katana 6M90A with angle Gripper
58 K_6M180=2, // Katana 6M180 (link length with Flange)
59 K_6M90B_F=3, // Katana 6M90B with Flange
60 K_6M90B_G=4 // Katana 6M90B with angle Gripper
61 };
62 
63 // multiply lengths to give them more weight relative to the angles in the
64 // inverse kinematics approximation of roboop --JHA
65 // [[in analyticalGuess the weight is more equalized, because it is calculated
66 // in mm (range typacally +/- 200-400) and degree (range typacally +/- 180),
67 // in roboop SI units are used: m (range typically +/- 0.2-0.4) and radian
68 // (range typically +/- 3.0). multiplying all lengths by about 10.0 for
69 // roboop calculations brings back a good precision in position.]]
70 const double LENGTH_MULTIPLIER = 10.0;
71 
72 const int MaxDof = 10;
73 
74 const int Dof_90 = 6;
75 const int Dof_180 = 5;
76 
78 //The matrices for the different Katana HW configurations:
79 // 1 sigma joint type (revolute=0, prismatic=1)
80 // 2 theta Denavit-Hartenberg parameter
81 // 3 d Denavit-Hartenberg parameter
82 // 4 a Denavit-Hartenberg parameter
83 // 5 alpha Denavit-Hartenberg parameter
84 // 6 theta_{min} minimum value of joint variable
85 // 7 theta_{max} maximum value of joint variable
86 // 8 theta_{off} joint offset
87 // 9 m mass of the link
88 // 10 c_x center of mass along axis $x$
89 // 11 c_y center of mass along axis $y$
90 // 12 c_z center of mass along axis $z$
91 // 13 I_{xx} element $xx$ of the inertia tensor matrix
92 // 14 I_{xy} element $xy$ of the inertia tensor matrix
93 // 15 I_{xz} element $xz$ of the inertia tensor matrix
94 // 16 I_{yy} element $yy$ of the inertia tensor matrix
95 // 17 I_{yz} element $yz$ of the inertia tensor matrix
96 // 18 I_{zz} element $zz$ of the inertia tensor matrix
97 // 19 I_m motor rotor inertia
98 // 20 Gr motor gear ratio
99 // 21 B motor viscous friction coefficient
100 // 22 C_f motor Coulomb friction coefficient
101 // 23 immobile flag for the kinematics and inverse kinematics
102 // (if true joint is locked, if false joint is free)
103 
104 // NewMat Real elements used in Katana6Mxxx_data[] are defined as double
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};
112 
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};
120 
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};
127 
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};
135 
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};
143 
144 // angle offset data
145 const double Angle_offset_90A_F[] = {-3.025529, 2.168572, -2.221804, 0.462512, 1.422443, 3.656465};
146 const double Angle_offset_90A_G[] = {-3.025529, 2.168572, -2.221804, 0.462512, 1.422443, 1.570796}; //[5] immobile 1.570796
147 const double Angle_offset_180[] = {-3.025529, 2.168572, -2.221804, 0.462512, 4.564036};
148 const double Angle_offset_90B_F[] = {-3.025529, 2.168572, -2.221804, 0.462512, 4.564036, 3.656465};
149 const double Angle_offset_90B_G[] = {-3.025529, 2.168572, -2.221804, 0.462512, 4.564036, 1.570796}; //[5] immobile 1.570796
150 
151 
152 // angle range data
153 const double Angle_range_90A_F[] = {6.03884, 2.443461, 4.363323, 4.014257, 5.969026, 5.742133};
154 const double Angle_range_90A_G[] = {6.03884, 2.443461, 4.363323, 4.014257, 5.969026, 0.0};
155 const double Angle_range_180[] = {6.03884, 2.443461, 4.363323, 4.014257, 5.969026};
156 const double Angle_range_90B_F[] = {6.03884, 2.443461, 4.363323, 4.014257, 5.969026, 5.742133};
157 const double Angle_range_90B_G[] = {6.03884, 2.443461, 4.363323, 4.014257, 5.969026, 0.0};
158 
159 // link length data
160 const double Link_length_90A_F[] = {0.19, 0.139, 0.1473, 0.036};
161 const double Link_length_90A_G[] = {0.19, 0.139, 0.1473, 0.1505};
162 const double Link_length_180[] = {0.19, 0.139, 0.1473, 0.041}; // for anglegripper: 0.1555
163 const double Link_length_90B_F[] = {0.19, 0.139, 0.1473, 0.036};
164 const double Link_length_90B_G[] = {0.19, 0.139, 0.1473, 0.1505};
165 
167 const int Encoder_per_cycle[] = {51200, 94976, 47488, 51200, 51200, 51200};
169 const int Encoder_offset[] = {31000, -31000, -31000, 31000, 31000, 31000};
171 const int Rotation_direction[] = {-1, -1, 1, 1, 1, 1};
172 
173 
175 
179 private:
180 
182 
184  int _type;
189  int _dof;
191  int _dom;
193  int _epc[MaxDof];
205  double _angleMin[MaxDof];
207  double _angleMax[MaxDof];
209  double _linkLength[4];
220  double _tcpOffset[4];
221 
223 
224  int sign(int value);
225  int sign(double value);
226  #ifdef WIN32
227  double round( double x);
228  #endif // ifdef WIN32
229  int initializeMembers();
230  int setAngleMinMax();
231  int initDofMat(int dof);
232  int angleArrMDH2vecK4D(const double arr[], std::vector<double>* vec);
233 
234  int invKin(std::vector<double> pose, std::vector<double> prev,
235  std::vector<double>& angle);
236  int invKin_bisec(std::vector<double> pose, std::vector<double> prev,
237  std::vector<double>& conf, int maxBisection);
238  int anaGuess(std::vector<double> pose, std::vector<double> prev,
239  std::vector<double>& angle);
240  bool checkConfig(std::vector<double> config, std::vector<double> pose,
241  double tol = 0.00001);
242 
243 public:
244 
246 
248  KinematicsLib();
250  // 3 (K_6M90B_F) or 4 (K_6M90B_G)
251  // sets default parameters and initializes kinematics.
252  KinematicsLib(int type);
254  ~KinematicsLib();
255 
257 
273  int setType(int type);
274 
291  int setMDH(std::vector<double> theta, std::vector<double> d,
292  std::vector<double> a, std::vector<double> alpha, int typeNr = -1);
293 
305  int setLinkLen(std::vector<double> links);
306 
316  int setImmob(int immobile);
317 
326  int setEPC(std::vector<int> epc);
327 
336  int setEncOff(std::vector<int> encOffset);
337 
348  int setRotDir(std::vector<int> rotDir);
349 
358  int setAngOff(std::vector<double> angleOffset);
359 
369  int setAngRan(std::vector<double> angleRange);
370 
379  int setTcpOff(std::vector<double> tcpOffset);
380 
382 
391  int getType();
392 
399  int getMaxDOF();
400 
407  int getDOF();
408 
415  int getDOM();
416 
426  int getMDH(std::vector<double>& theta, std::vector<double>& d,
427  std::vector<double>& a, std::vector<double>& alpha);
428 
433  int getImmob();
434 
440  int getEPC(std::vector<int>& epc);
441 
447  int getEncOff(std::vector<int>& encOffset);
448 
454  int getRotDir(std::vector<int>& rotDir);
455 
461  int getAngOff(std::vector<double>& angleOffset);
462 
468  int getAngRan(std::vector<double>& angleRange);
469 
475  int getAngStop(std::vector<double>& angleStop);
476 
482  int getAngMin(std::vector<double>& angleMin);
483 
489  int getAngMax(std::vector<double>& angleMax);
490 
496  int getTcpOff(std::vector<double>& tcpOffset);
497 
503  int getVersion(std::vector<int>& version);
504 
506 
515  int init();
516 
518 
527  int K4D2mDHAng(std::vector<double> angleK4D, std::vector<double>& angleMDH);
528 
537  int mDH2K4DAng(std::vector<double> angleMDH, std::vector<double>& angleK4D);
538 
540 
547  int enc2rad(std::vector<int> encoders, std::vector<double>& angles);
548 
555  int rad2enc(std::vector<double> angles, std::vector<int>& encoders);
556 
558 
565  int directKinematics(std::vector<double> angles, std::vector<double>& pose);
566 
574  int inverseKinematics(std::vector<double> pose, std::vector<double> prev,
575  std::vector<double>& angles, int maxBisection = 0);
576 
577 };
578 
579 #endif //_KINEMATICS_H_
int _rotDir[MaxDof]
Rotation direction.
Definition: kinematics.h:197
const double Link_length_90A_G[]
Definition: kinematics.h:161
const double Link_length_180[]
Definition: kinematics.h:162
const double Angle_range_90A_F[]
Definition: kinematics.h:153
FloatVector FloatVector FloatVector int typeNr
FloatVector * prev
Kinematics class using the kinematics lib.
Definition: kinematics.h:178
const double Link_length_90B_G[]
Definition: kinematics.h:164
const double Angle_range_180[]
Definition: kinematics.h:155
int setEncOff(std::vector< int > encOffset)
This sets the encoder offsets.
Definition: kinematics.cpp:422
int getImmob()
Get the immobile flag of the last joint.
Definition: kinematics.cpp:607
int sign(int value)
Definition: kinematics.cpp:27
const int Rotation_direction[]
Rotation direction.
Definition: kinematics.h:171
const Real Katana6M90A_G_data[]
Definition: kinematics.h:113
int setAngRan(std::vector< double > angleRange)
This sets the angle range.
Definition: kinematics.cpp:510
const int Dof_90
Definition: kinematics.h:74
Robots class definitions.
double _tcpOffset[4]
TCP offset.
Definition: kinematics.h:220
int getAngStop(std::vector< double > &angleStop)
Get angle stop.
Definition: kinematics.cpp:666
int rad2enc(std::vector< double > angles, std::vector< int > &encoders)
Converts angles to encoders.
Definition: kinematics.cpp:826
const int Encoder_offset[]
Encoder offset.
Definition: kinematics.h:169
int setRotDir(std::vector< int > rotDir)
This sets the rotation direction.
Definition: kinematics.cpp:434
Matrix _data
Definition: kinematics.h:187
const double Angle_offset_90A_F[]
Definition: kinematics.h:145
double Real
Definition: include.h:307
int getAngRan(std::vector< double > &angleRange)
Get the angle range.
Definition: kinematics.cpp:655
#define mPi
Definition: kinematics.h:25
FloatVector * pose
const Real Katana6M90A_F_data[]
Definition: kinematics.h:105
~KinematicsLib()
Destructor.
Definition: kinematics.cpp:21
const double Angle_range_90B_G[]
Definition: kinematics.h:157
Utility header file.
const Real Katana6M90B_G_data[]
Definition: kinematics.h:136
int initDofMat(int dof)
Definition: kinematics.cpp:95
int setAngleMinMax()
Definition: kinematics.cpp:78
FloatVector * angleK4D
const double Link_length_90B_F[]
Definition: kinematics.h:163
int getEncOff(std::vector< int > &encOffset)
Get the encoder offsets.
Definition: kinematics.cpp:622
const int Encoder_per_cycle[]
Encoder per cycle.
Definition: kinematics.h:167
int _dom
Degree of mobility.
Definition: kinematics.h:191
double _angleMin[MaxDof]
Angle min.
Definition: kinematics.h:205
bool _angRanInit
Angle range.
Definition: kinematics.h:202
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.
Definition: kinematics.cpp:323
FloatVector * d
int invKin(std::vector< double > pose, std::vector< double > prev, std::vector< double > &angle)
Definition: kinematics.cpp:897
int getAngOff(std::vector< double > &angleOffset)
Get the angle offsets.
Definition: kinematics.cpp:644
int _encoderOffset[MaxDof]
Encoder offset.
Definition: kinematics.h:195
int getDOF()
Get the degree of freedom.
Definition: kinematics.cpp:581
FloatVector * angleMDH
double _thetaimmobile
Definition: kinematics.h:214
const Real Katana6M90B_F_data[]
Definition: kinematics.h:128
Modified DH notation robot class.
Definition: robot.h:389
FloatVector FloatVector int maxBisection
const int Dof_180
Definition: kinematics.h:75
_T atan1(_T in1, _T in2)
Definition: kinematics.h:36
int getDOM()
Get the degree of mobility.
Definition: kinematics.cpp:585
const double Angle_range_90B_F[]
Definition: kinematics.h:156
int anaGuess(std::vector< double > pose, std::vector< double > prev, std::vector< double > &angle)
Definition: kinematics.cpp:975
int _epc[MaxDof]
Encoder per cycle.
Definition: kinematics.h:193
int init()
This initializes the kinematics.
Definition: kinematics.cpp:730
int getAngMin(std::vector< double > &angleMin)
Get angle min.
Definition: kinematics.cpp:684
int invKin_bisec(std::vector< double > pose, std::vector< double > prev, std::vector< double > &conf, int maxBisection)
Definition: kinematics.cpp:940
The usual rectangular matrix.
Definition: newmat.h:625
int setAngOff(std::vector< double > angleOffset)
This sets the angle offsets.
Definition: kinematics.cpp:450
bool _matrixInit
Matrices for mDH, angle range and immobile data.
Definition: kinematics.h:186
mRobot _robot
Roboop robot class.
Definition: kinematics.h:211
const double Angle_offset_180[]
Definition: kinematics.h:147
int _dof
Degree of freedom.
Definition: kinematics.h:189
const int MaxDof
Definition: kinematics.h:72
int mDH2K4DAng(std::vector< double > angleMDH, std::vector< double > &angleK4D)
This converts angles from mDH to Katana4D convention.
Definition: kinematics.cpp:776
int getType()
Get the robot type.
Definition: kinematics.cpp:573
FloatVector FloatVector * a
FloatVector * angle
double _angleOffset[MaxDof]
Definition: kinematics.h:200
Quaternion class.
const double Angle_offset_90B_F[]
Definition: kinematics.h:148
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.
Definition: kinematics.cpp:393
const double Angle_range_90A_G[]
Definition: kinematics.h:154
bool _angOffInit
Angle offset.
Definition: kinematics.h:199
double _angleRange[MaxDof]
Definition: kinematics.h:203
const double LENGTH_MULTIPLIER
Definition: kinematics.h:70
int getTcpOff(std::vector< double > &tcpOffset)
Get the tcp offset.
Definition: kinematics.cpp:710
FloatVector FloatVector FloatVector * alpha
KinematicsLib()
Constructor.
Definition: kinematics.cpp:11
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)
Definition: kinematics.cpp:355
AnaGuess::Kinematics * _anaGuess
Analytical guess.
Definition: kinematics.h:216
int getVersion(std::vector< int > &version)
Get the version number of the library.
Definition: kinematics.cpp:721
bool _initialized
Kinematic initialized.
Definition: kinematics.h:218
int setTcpOff(std::vector< double > tcpOffset)
This sets the tcp offset.
Definition: kinematics.cpp:561
const Real Katana6M180_data[]
Definition: kinematics.h:121
int getEPC(std::vector< int > &epc)
Get the encoders per cycle.
Definition: kinematics.cpp:611
int K4D2mDHAng(std::vector< double > angleK4D, std::vector< double > &angleMDH)
This converts angles from Katana4D to mDH convention.
Definition: kinematics.cpp:740
int directKinematics(std::vector< double > angles, std::vector< double > &pose)
Calculates the direct kinematics.
Definition: kinematics.cpp:840
int getRotDir(std::vector< int > &rotDir)
Get the rotation direction.
Definition: kinematics.cpp:633
int enc2rad(std::vector< int > encoders, std::vector< double > &angles)
Converts encoders to angles.
Definition: kinematics.cpp:812
int angleArrMDH2vecK4D(const double arr[], std::vector< double > *vec)
Definition: kinematics.cpp:104
int _type
Robot Type.
Definition: kinematics.h:184
int setType(int type)
This sets the robot type.
Definition: kinematics.cpp:118
katana_type
Definition: kinematics.h:55
int _immobile
Last joint is immobile (eg. K_6M90A_G, K_6M90B_G), _dom = _dof - 1.
Definition: kinematics.h:213
const double Angle_offset_90B_G[]
Definition: kinematics.h:149
double _angleMax[MaxDof]
Angle max.
Definition: kinematics.h:207
int getMaxDOF()
Get the maximum degree of freedom.
Definition: kinematics.cpp:577
int getAngMax(std::vector< double > &angleMax)
Get angle max.
Definition: kinematics.cpp:697
int setEPC(std::vector< int > epc)
This sets the encoders per cycle.
Definition: kinematics.cpp:410
std::vector< int > encoders
Definition: kni_wrapper.cpp:29
double _linkLength[4]
Link length (for defined types)
Definition: kinematics.h:209
const double Link_length_90A_F[]
Definition: kinematics.h:160
const double Angle_offset_90A_G[]
Definition: kinematics.h:146
int getMDH(std::vector< double > &theta, std::vector< double > &d, std::vector< double > &a, std::vector< double > &alpha)
Get the modified Denavit-Hartenberg parameters.
Definition: kinematics.cpp:589
int initializeMembers()
Definition: kinematics.cpp:63


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44