EAIK 1.0.0__tar.gz → 1.2.0__tar.gz

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
Files changed (53) hide show
  1. {eaik-1.0.0 → eaik-1.2.0}/CPP/external/ik-geo/cpp/subproblems/sp.cpp +124 -60
  2. {eaik-1.0.0 → eaik-1.2.0}/CPP/external/ik-geo/cpp/subproblems/sp.h +1 -1
  3. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/CMakeLists.txt +1 -1
  4. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/EAIK.cpp +65 -33
  5. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/EAIK.h +12 -0
  6. eaik-1.2.0/CPP/src/IK/1R_IK.cpp +48 -0
  7. eaik-1.2.0/CPP/src/IK/2R_IK.cpp +89 -0
  8. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/IK/3R_IK.cpp +6 -8
  9. eaik-1.2.0/CPP/src/IK/4R_IK.cpp +391 -0
  10. eaik-1.2.0/CPP/src/IK/5R_IK.cpp +714 -0
  11. eaik-1.2.0/CPP/src/IK/6R_IK.cpp +707 -0
  12. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/IK/CMakeLists.txt +2 -2
  13. eaik-1.2.0/CPP/src/IK/IKS.h +218 -0
  14. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/IK/utils/kinematic_utils.h +1 -0
  15. eaik-1.0.0/CPP/src/utils/kinematic_remodelling.cpp → eaik-1.2.0/CPP/src/utils/kinematic_remodeling.cpp +21 -21
  16. eaik-1.0.0/CPP/src/utils/kinematic_remodelling.h → eaik-1.2.0/CPP/src/utils/kinematic_remodeling.h +4 -3
  17. eaik-1.2.0/LICENSE +28 -0
  18. eaik-1.2.0/PKG-INFO +155 -0
  19. eaik-1.2.0/README.md +132 -0
  20. {eaik-1.0.0 → eaik-1.2.0}/pyproject.toml +7 -5
  21. {eaik-1.0.0 → eaik-1.2.0}/setup.py +8 -5
  22. eaik-1.2.0/src/EAIK.egg-info/PKG-INFO +155 -0
  23. {eaik-1.0.0 → eaik-1.2.0}/src/EAIK.egg-info/SOURCES.txt +11 -11
  24. eaik-1.2.0/src/eaik/IK_DH.py +26 -0
  25. eaik-1.2.0/src/eaik/IK_HP.py +24 -0
  26. eaik-1.2.0/src/eaik/IK_Homogeneous.py +42 -0
  27. eaik-1.2.0/src/eaik/IK_Robot.py +79 -0
  28. eaik-1.2.0/src/eaik/IK_URDF.py +40 -0
  29. {eaik-1.0.0 → eaik-1.2.0}/src/eaik/pybindings/eaik_pybindings.cpp +6 -1
  30. eaik-1.0.0/CPP/src/IK/General_IK.cpp +0 -308
  31. eaik-1.0.0/CPP/src/IK/IKS.h +0 -84
  32. eaik-1.0.0/CPP/src/IK/Spherical_IK.cpp +0 -252
  33. eaik-1.0.0/LICENSE +0 -674
  34. eaik-1.0.0/PKG-INFO +0 -801
  35. eaik-1.0.0/README.md +0 -106
  36. eaik-1.0.0/src/EAIK.egg-info/PKG-INFO +0 -801
  37. eaik-1.0.0/src/eaik/IK_DH.py +0 -62
  38. eaik-1.0.0/src/eaik/IK_Homogeneous.py +0 -72
  39. eaik-1.0.0/src/eaik/IK_URDF.py +0 -70
  40. eaik-1.0.0/src/eaik/utils/frame_trafo_helpers.py +0 -14
  41. eaik-1.0.0/src/eaik/utils/generate_spherical_wrist.py +0 -199
  42. eaik-1.0.0/src/eaik/utils/remodel_kinematics.py +0 -74
  43. eaik-1.0.0/src/eaik/utils/spatial.py +0 -69
  44. eaik-1.0.0/src/eaik/utils/spherical_wrist_checks.py +0 -127
  45. {eaik-1.0.0 → eaik-1.2.0}/CPP/external/ik-geo/cpp/subproblems/CMakeLists.txt +0 -0
  46. {eaik-1.0.0 → eaik-1.2.0}/CPP/src/IK/utils/kinematic_utils.cpp +0 -0
  47. {eaik-1.0.0 → eaik-1.2.0}/MANIFEST.in +0 -0
  48. {eaik-1.0.0 → eaik-1.2.0}/setup.cfg +0 -0
  49. {eaik-1.0.0 → eaik-1.2.0}/src/EAIK.egg-info/dependency_links.txt +0 -0
  50. {eaik-1.0.0 → eaik-1.2.0}/src/EAIK.egg-info/requires.txt +0 -0
  51. {eaik-1.0.0 → eaik-1.2.0}/src/EAIK.egg-info/top_level.txt +0 -0
  52. {eaik-1.0.0 → eaik-1.2.0}/src/eaik/__init__.py +0 -0
  53. {eaik-1.0.0/src/eaik/utils → eaik-1.2.0/src/eaik/pybindings}/__init__.py +0 -0
@@ -51,50 +51,16 @@ namespace IKS
51
51
 
52
52
  std::vector<std::complex<double>> quartic_roots(const Eigen::Matrix<double, 1, 5> &poly)
53
53
  {
54
+ Eigen::PolynomialSolver<double, Eigen::Dynamic> solver;
55
+ solver.compute(poly);
56
+ const Eigen::PolynomialSolver<double, Eigen::Dynamic>::RootsType &roots = solver.roots();
54
57
 
55
- const std::complex<double> i = std::complex<double>(0, 0);
56
-
57
- std::vector<std::complex<double>> roots;
58
-
59
- double A = poly(0, 0), B = poly(0, 1), C = poly(0, 2), D = poly(0, 3), E = poly(0, 4);
60
-
61
- std::complex<double> alpha = -0.375 * B * B / (A * A) + C / A;
62
- std::complex<double> beta = 0.125 * B * B * B / (A * A * A) - 0.5 * B * C / (A * A) + D / A;
63
- std::complex<double> gamma = -B * B * B * B * 3. / (A * A * A * A * 256.) + C * B * B / (A * A * A * 16.) - B * D / (A * A * 4.) + E / A;
64
-
65
- if (fabs(beta.real()) < ZERO_THRESH && fabs(beta.imag()) < ZERO_THRESH)
66
- {
67
- std::complex<double> tmp = sqrt(alpha * alpha - gamma * 4. + i);
68
- roots.push_back(-B / (A * 4.) + sqrt((-alpha + tmp) / 2. + i));
69
- roots.push_back(-B / (A * 4.) - sqrt((-alpha + tmp) / 2. + i));
70
- roots.push_back(-B / (A * 4.) + sqrt((-alpha - tmp) / 2. + i));
71
- roots.push_back(-B / (A * 4.) - sqrt((-alpha - tmp) / 2. + i));
72
- return roots;
58
+ std::vector<std::complex<double>> result(roots.size());
59
+ for (int i = 0; i < roots.size(); ++i) {
60
+ result[i] = roots[i];
73
61
  }
74
62
 
75
- std::complex<double> P = -alpha * alpha / 12. - gamma;
76
- std::complex<double> Q = -alpha * alpha * alpha / 108. + alpha * gamma / 3. - beta * beta * 0.125;
77
- std::complex<double> R = -Q * 0.5 + sqrt(Q * Q * 0.25 + P * P * P / 27. + i);
78
- std::complex<double> U = pow(R, 1. / 3);
79
-
80
- std::complex<double> y;
81
- if (fabs(U.real()) < ZERO_THRESH && fabs(U.imag()) < ZERO_THRESH)
82
- {
83
- y = -alpha * 5. / 6. - pow(Q, 1. / 3);
84
- }
85
- else
86
- {
87
- y = -alpha * 5. / 6. + U - P / (3. * U);
88
- }
89
-
90
- std::complex<double> W = sqrt(alpha + 2. * y + i);
91
-
92
- roots.push_back(-B / (A * 4.) + (W + sqrt(-(alpha * 3. + 2. * y + beta * 2. / W))) / 2.);
93
- roots.push_back(-B / (A * 4.) + (W - sqrt(-(alpha * 3. + 2. * y + beta * 2. / W))) / 2.);
94
- roots.push_back(-B / (A * 4.) - (W + sqrt(-(alpha * 3. + 2. * y - beta * 2. / W))) / 2.);
95
- roots.push_back(-B / (A * 4.) - (W - sqrt(-(alpha * 3. + 2. * y - beta * 2. / W))) / 2.);
96
-
97
- return roots;
63
+ return result;
98
64
  }
99
65
 
100
66
  std::vector<std::pair<double, double>> solve_2_ellipse_numeric(const Eigen::Vector2d &xm1, const Eigen::Matrix<double, 2, 2> &xn1,
@@ -105,7 +71,7 @@ namespace IKS
105
71
  xm1'*xm1 + xi'*xn1'*xn1*xi + xm1'*xn1*xi == 1
106
72
  xm2'*xm2 + xi'*xn2'*xn2*xi + xm2'*xn2*xi == 1
107
73
  Where xi = [xi_1; xi_2] */
108
- const double EPSILON = ZERO_THRESH;
74
+ const double EPSILON = 1e-5;
109
75
  Eigen::Matrix<double, 2, 2> A_1 = xn1.transpose() * xn1;
110
76
  double a = A_1.coeffRef(0, 0);
111
77
  double b = 2 * A_1.coeffRef(1, 0);
@@ -143,7 +109,7 @@ namespace IKS
143
109
  double z4 = a*a*c1*c1 - 2.0*a*c1*a1*c + a1*a1*c*c - b*a*b1*c1 - b*b1*a1*c + b*b*a1*c1 +
144
110
  c*a*b1*b1;
145
111
  Eigen::Matrix<double, 1, 5> z;
146
- z << z4, z3, z2, z1, z0;
112
+ z << z0,z1, z2, z3, z4;
147
113
  std::vector<std::complex<double>> roots = quartic_roots(z);
148
114
 
149
115
  std::vector<std::pair<double, double>> xi;
@@ -232,10 +198,19 @@ namespace IKS
232
198
  a.row(1) = -k.cross(kxp);
233
199
 
234
200
  const Eigen::Vector2d x = a * p2;
235
- theta = std::atan2(x.x(), x.y());
236
201
 
237
- _solution_is_ls = std::fabs(p1.norm() - p2.norm()) > ZERO_THRESH ||
238
- std::fabs(k.dot(p1) - k.dot(p2)) > ZERO_THRESH;
202
+ if(x.norm() > ZERO_THRESH)
203
+ {
204
+ theta = std::atan2(x.x(), x.y());
205
+ _solution_is_ls = std::fabs(p1.norm() - p2.norm()) > ZERO_THRESH ||
206
+ std::fabs(k.dot(p1) - k.dot(p2)) > ZERO_THRESH;
207
+ }
208
+ else
209
+ {
210
+ theta = 0;
211
+ _solution_is_ls = true;
212
+ }
213
+
239
214
 
240
215
  is_calculated = true;
241
216
  }
@@ -402,6 +377,7 @@ namespace IKS
402
377
  //std::cout<<"Warning! - minimization of subproblem 3 is indipendent of theta. This may indicate redundancy"<<std::endl;
403
378
  is_calculated = true;
404
379
  theta.push_back(0); // Default angle
380
+ _solution_is_ls = true;
405
381
  return;
406
382
  }
407
383
 
@@ -415,7 +391,7 @@ namespace IKS
415
391
 
416
392
  const Eigen::Vector2d x_ls = a_1.transpose() * (-2.0 * p2 * b / norm_a_sq);
417
393
 
418
- if (x_ls.squaredNorm() > 1.0)
394
+ if (x_ls.squaredNorm() > 1.0 - ZERO_THRESH || 1.0 - b * b / norm_a_sq < 0)
419
395
  {
420
396
  theta.push_back(std::atan2(x_ls.x(), x_ls.y()));
421
397
  _solution_is_ls = true;
@@ -431,6 +407,7 @@ namespace IKS
431
407
 
432
408
  theta.push_back(std::atan2(sc_1.x(), sc_1.y()));
433
409
  theta.push_back(std::atan2(sc_2.x(), sc_2.y()));
410
+
434
411
  _solution_is_ls = false;
435
412
  }
436
413
 
@@ -489,25 +466,32 @@ namespace IKS
489
466
  const Eigen::Vector2d a = h.transpose() * a_1;
490
467
 
491
468
  const double b = d - (h.transpose() * k * k.transpose() * p).x();
492
-
493
469
  const double norm_a_sq = a.squaredNorm();
494
470
  const Eigen::Vector2d x_ls = a_1.transpose() * h * b;
495
471
 
496
- if (norm_a_sq > b * b)
472
+ if (norm_a_sq - b * b > 0)
497
473
  {
498
- const double xi = std::sqrt((norm_a_sq - b * b));
474
+ const double xi = std::sqrt(norm_a_sq - b * b );
499
475
  const Eigen::Vector2d a_perp_tilde(a.y(), -a.x());
500
476
 
501
477
  const Eigen::Vector2d sc_1 = x_ls + xi * a_perp_tilde;
502
478
  const Eigen::Vector2d sc_2 = x_ls - xi * a_perp_tilde;
503
479
 
504
480
  theta.push_back(std::atan2(sc_1.x(), sc_1.y()));
505
- theta.push_back(std::atan2(sc_2.x(), sc_2.y()));
481
+ theta.push_back(std::atan2(sc_2.x(), sc_2.y()));
506
482
  _solution_is_ls = false;
507
483
  }
508
484
  else
509
485
  {
510
- theta.push_back(std::atan2(x_ls.x(), x_ls.y()));
486
+ if (x_ls.norm() < ZERO_THRESH)
487
+ {
488
+ theta.push_back(0);
489
+ }
490
+ else
491
+ {
492
+ theta.push_back(std::atan2(x_ls.x(), x_ls.y()));
493
+ }
494
+
511
495
  _solution_is_ls = true;
512
496
  }
513
497
 
@@ -562,7 +546,7 @@ namespace IKS
562
546
 
563
547
  void SP5::solve()
564
548
  {
565
- const double EPSILON = ZERO_THRESH; // Should this be different?
549
+ const double EPSILON = 1e-6; // Should this be different?
566
550
  std::vector<double> theta;
567
551
  theta.reserve(8);
568
552
 
@@ -582,7 +566,7 @@ namespace IKS
582
566
 
583
567
  const Eigen::Matrix<double, 1, 5> eqn_real = convolution_3(rhs, rhs) - 4.0 * convolution_3(p_13_sq, r_1);
584
568
 
585
- const std::vector<std::complex<double>> all_roots = quartic_roots(eqn_real);
569
+ std::vector<std::complex<double>> all_roots = quartic_roots(eqn_real.row(0).reverse());
586
570
 
587
571
  std::vector<double> h_vec;
588
572
  for (const auto &root : all_roots)
@@ -593,6 +577,16 @@ namespace IKS
593
577
  }
594
578
  }
595
579
 
580
+ // No analytical solution found - use all roots and decide later for valid solutions
581
+ if (h_vec.size() == 0)
582
+ {
583
+ for (const auto &root : all_roots)
584
+ {
585
+ h_vec.push_back(root.real());
586
+ }
587
+ _solution_is_ls = true;
588
+ }
589
+
596
590
  const Eigen::Vector3d kxp1 = k1.cross(p1);
597
591
  const Eigen::Vector3d kxp3 = k3.cross(p3);
598
592
 
@@ -611,6 +605,10 @@ namespace IKS
611
605
  j << 0, 1,
612
606
  -1, 0;
613
607
 
608
+ // We save angle combinations w.r.t. their error in std::fabs((v1 - h * k2).norm() - (v3 - h * k2).norm())
609
+ // If no combination reaches our threshold we can then still output the best approximate solution
610
+ std::vector<std::tuple<double, double, double, double>> norm_errors_angles;
611
+
614
612
  for (const auto &h : h_vec)
615
613
  {
616
614
  Eigen::Vector2d const_1 = a_1.transpose() * k2 * (h - delta_1);
@@ -648,19 +646,76 @@ namespace IKS
648
646
  Eigen::Vector3d v1 = a_1 * sc_1 + p1_s;
649
647
  Eigen::Vector3d v3 = a_3 * sc_3 + p3_s;
650
648
 
651
- if (std::fabs((v1 - h * k2).norm() - (v3 - h * k2).norm()) < EPSILON)
649
+ const double norm_equation_error = std::fabs(v1.norm() - v3.norm());
650
+ if (norm_equation_error < 1e-3)
652
651
  {
653
652
  SP1 sp(v3, v1, k2);
654
653
  sp.solve();
654
+ _solution_is_ls |= sp.solution_is_ls();
655
+
656
+ if (sc_1.norm() > ZERO_THRESH)
657
+ {
658
+ theta_1.push_back(std::atan2(sc_1.x(), sc_1.y()));
659
+ }
660
+ else
661
+ {
662
+ theta_1.push_back(0);
663
+ _solution_is_ls = true;
664
+ }
665
+
666
+ if (sc_3.norm() > ZERO_THRESH)
667
+ {
668
+ theta_3.push_back(std::atan2(sc_3.x(), sc_3.y()));
669
+ }
670
+ else
671
+ {
672
+ theta_3.push_back(0);
673
+ _solution_is_ls = true;
674
+ }
655
675
 
656
- theta_1.push_back(std::atan2(sc_1.x(), sc_1.y()));
657
676
  theta_2.push_back(sp.get_theta());
658
- theta_3.push_back(std::atan2(sc_3.x(), sc_3.y()));
677
+ }
678
+ else
679
+ {
680
+ SP1 sp(v3, v1, k2);
681
+ sp.solve();
682
+
683
+ double approx_t1 = 0;
684
+ double approx_t2 = 0;
685
+ double approx_t3 = 0;
686
+
687
+ if (sc_1.norm() > ZERO_THRESH)
688
+ {
689
+ approx_t1 = std::atan2(sc_1.x(), sc_1.y());
690
+ }
691
+
692
+ if (sc_3.norm() > ZERO_THRESH)
693
+ {
694
+ approx_t3 = std::atan2(sc_3.x(), sc_3.y());
695
+ }
696
+
697
+ approx_t2 = sp.get_theta();
698
+
699
+ norm_errors_angles.push_back({norm_equation_error, approx_t1, approx_t2, approx_t3});
700
+ _solution_is_ls = true;
659
701
  }
660
702
  }
661
703
  }
662
704
 
663
- reduce_solutionset();
705
+ // Check if any valid angles were found - if not, use best approximate solution
706
+ if (theta_1.size() == 0)
707
+ {
708
+ // Sort by error
709
+ std::sort(norm_errors_angles.begin(), norm_errors_angles.end(), [](const std::tuple<double, double, double, double>& a, const std::tuple<double, double, double, double>& b) {
710
+ return std::get<0>(a) < std::get<0>(b);
711
+ });
712
+ theta_1.push_back(std::get<1>(norm_errors_angles.at(0)));
713
+ theta_2.push_back(std::get<2>(norm_errors_angles.at(0)));
714
+ theta_3.push_back(std::get<3>(norm_errors_angles.at(0)));
715
+ _solution_is_ls = true;
716
+ }
717
+
718
+ //reduce_solutionset();
664
719
  is_calculated = true;
665
720
  }
666
721
 
@@ -888,8 +943,17 @@ namespace IKS
888
943
  for (const auto[xi_1, xi_2] : xi)
889
944
  {
890
945
  Eigen::Matrix<double, 4, 1> x = x_min + x_null_1 * xi_1 + x_null_2 * xi_2;
891
- theta_1.push_back(atan2(x(0, 0), x(1, 0)));
892
- theta_2.push_back(atan2(x(2, 0), x(3, 0)));
946
+
947
+ if(x.norm() < ZERO_THRESH)
948
+ {
949
+ theta_1.push_back(0);
950
+ theta_2.push_back(0);
951
+ }
952
+ else
953
+ {
954
+ theta_1.push_back(atan2(x(0, 0), x(1, 0)));
955
+ theta_2.push_back(atan2(x(2, 0), x(3, 0)));
956
+ }
893
957
  }
894
958
 
895
959
  is_calculated = true;
@@ -8,7 +8,7 @@ namespace IKS
8
8
  {
9
9
 
10
10
  #ifndef ZERO_THRESH
11
- #define ZERO_THRESH 1e-8
11
+ #define ZERO_THRESH 1e-12
12
12
  #endif
13
13
 
14
14
  std::pair<Eigen::Vector2d, Eigen::Vector3d> cone_polynomials(const Eigen::Vector3d &p0_i, const Eigen::Vector3d &k_i, const Eigen::Vector3d &p_i, const Eigen::Vector3d &p_i_s, const Eigen::Vector3d &k2);
@@ -9,7 +9,7 @@ endif()
9
9
  set(CMAKE_CXX_STANDARD 17)
10
10
  set(CMAKE_CXX_FLAGS_RELEASE "-O3")
11
11
 
12
- set(sources EAIK.cpp ${CMAKE_CURRENT_SOURCE_DIR}/utils/kinematic_remodelling.cpp ${CMAKE_CURRENT_SOURCE_DIR}/IK/utils/kinematic_utils.cpp)
12
+ set(sources EAIK.cpp ${CMAKE_CURRENT_SOURCE_DIR}/utils/kinematic_remodeling.cpp ${CMAKE_CURRENT_SOURCE_DIR}/IK/utils/kinematic_utils.cpp)
13
13
 
14
14
  add_library(EAIK ${sources})
15
15
  target_include_directories(EAIK PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_SOURCE_DIR}/utils ${CMAKE_CURRENT_SOURCE_DIR}/IK ${CMAKE_CURRENT_SOURCE_DIR}/IK/utils)
@@ -3,7 +3,7 @@
3
3
  #include <thread>
4
4
  #include <mutex>
5
5
 
6
- #include "kinematic_remodelling.h"
6
+ #include "kinematic_remodeling.h"
7
7
  #include "kinematic_utils.h"
8
8
  #include "EAIK.h"
9
9
 
@@ -34,8 +34,8 @@ namespace EAIK
34
34
  throw std::runtime_error("Wrong input dimensions for H and P. Note that #P = #H+1.");
35
35
  }
36
36
 
37
- Eigen::MatrixXd P_remodelled;
38
- Eigen::MatrixXd H_remodelled;
37
+ Eigen::MatrixXd P_remodeled;
38
+ Eigen::MatrixXd H_remodeled;
39
39
 
40
40
  // Insert fixed axes (e.g., to cope with >6DOF manipulators) into the kinematic chain
41
41
  if(fixed_axes.size()>0)
@@ -44,54 +44,81 @@ namespace EAIK
44
44
  std::sort(this->fixed_axes.begin(), this->fixed_axes.end(), [](const std::pair<int, double>& a, const std::pair<int, double>& b) {return a.first < b.first;});
45
45
 
46
46
  const auto&[H_part, P_part, R6T_part] = partial_joint_parametrization(H, P, fixed_axes, R6T);
47
- P_remodelled = remodel_kinematics(H_part, P_part, ZERO_THRESHOLD, AXIS_INTERSECT_THRESHOLD);
48
- H_remodelled = H_part;
47
+ P_remodeled = remodel_kinematics(H_part, P_part, ZERO_THRESHOLD, AXIS_INTERSECT_THRESHOLD);
48
+ H_remodeled = H_part;
49
49
  this->R6T_partial = R6T_part;
50
50
  }
51
51
  else
52
52
  {
53
- P_remodelled = remodel_kinematics(H, P, ZERO_THRESHOLD, AXIS_INTERSECT_THRESHOLD);
54
- H_remodelled = H;
53
+ P_remodeled = remodel_kinematics(H, P, ZERO_THRESHOLD, AXIS_INTERSECT_THRESHOLD);
54
+ H_remodeled = H;
55
55
  this->R6T_partial = R6T;
56
56
  }
57
- switch (H_remodelled.cols())
57
+ switch (H_remodeled.cols())
58
58
  {
59
59
  case 6:
60
- // Check if last three axes intersect
61
- if (P_remodelled.col(P_remodelled.cols()-3).norm() < ZERO_THRESHOLD && P_remodelled.col(P_remodelled.cols()-2).norm() < ZERO_THRESHOLD)
62
- {
63
- spherical_wrist = true;
64
- bot_kinematics = std::make_unique<IKS::Spherical_Wrist_Robot>(H_remodelled, P_remodelled);
65
- original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
66
- }
67
- else if(P_remodelled.col(1).norm() < ZERO_THRESHOLD && P_remodelled.col(2).norm() < ZERO_THRESHOLD)
68
- {
69
- // Spherical wrist is located at the base of the robot
70
- spherical_wrist = true;
71
- const auto&[H_reversed, P_reversed] = IKS::reverse_kinematic_chain(H_remodelled, P_remodelled);
72
- bot_kinematics = std::make_unique<IKS::Spherical_Wrist_Robot>(H_reversed, P_reversed, true);
73
- original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
74
- }
75
- else
76
- {
77
- bot_kinematics = std::make_unique<IKS::General_6R>(H_remodelled, P_remodelled);
78
- original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
79
- }
60
+ bot_kinematics = std::make_unique<IKS::General_6R>(H_remodeled, P_remodeled);
61
+ original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
62
+ break;
63
+ case 5:
64
+ bot_kinematics = std::make_unique<IKS::General_5R>(H_remodeled, P_remodeled);
65
+ original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
80
66
  break;
81
-
67
+ case 4:
68
+ bot_kinematics = std::make_unique<IKS::General_4R>(H_remodeled, P_remodeled);
69
+ original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
70
+ break;
82
71
  case 3:
83
- bot_kinematics = std::make_unique<IKS::General_3R>(H_remodelled, P_remodelled);
84
- original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
72
+ bot_kinematics = std::make_unique<IKS::General_3R>(H_remodeled, P_remodeled);
73
+ original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
74
+ break;
75
+ case 2:
76
+ bot_kinematics = std::make_unique<IKS::General_2R>(H_remodeled, P_remodeled);
77
+ original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
78
+ break;
79
+ case 1:
80
+ bot_kinematics = std::make_unique<IKS::General_1R>(H_remodeled, P_remodeled);
81
+ original_kinematics = std::make_unique<IKS::General_Robot>(H, P);
85
82
  break;
86
83
  default:
87
- throw std::runtime_error("Currently, only 6R and 3R Robots are solvable with EAIK.");
84
+ throw std::runtime_error("Currently, only 1-6R robots are solvable with EAIK. Consider locking redundant joints.");
88
85
  break;
89
86
  }
90
87
  }
91
88
 
92
89
 
90
+ Eigen::MatrixXd Robot::get_remodeled_H() const
91
+ {
92
+ return bot_kinematics->get_H();
93
+ }
94
+
95
+ Eigen::MatrixXd Robot::get_remodeled_P() const
96
+ {
97
+ return bot_kinematics->get_P();
98
+ }
99
+
100
+ Eigen::MatrixXd Robot::get_original_H() const
101
+ {
102
+ return original_kinematics->get_H();
103
+ }
104
+
105
+ Eigen::MatrixXd Robot::get_original_P() const
106
+ {
107
+ return original_kinematics->get_P();
108
+ }
109
+
110
+ std::string Robot::get_kinematic_family() const
111
+ {
112
+ return bot_kinematics->get_kinematic_family();
113
+ }
114
+
93
115
  IKS::IK_Solution Robot::calculate_IK(const IKS::Homogeneous_T &ee_position_orientation) const
94
116
  {
117
+ if (!bot_kinematics->has_known_decomposition())
118
+ {
119
+ throw std::runtime_error(decomposition_unknown_exception_info);
120
+ }
121
+
95
122
  IKS::Homogeneous_T ee_06_rot = ee_position_orientation;
96
123
  ee_06_rot.block<3,3>(0,0) *= R6T_partial.transpose();
97
124
  IKS::IK_Solution solution = bot_kinematics->calculate_IK(ee_06_rot);
@@ -110,6 +137,11 @@ namespace EAIK
110
137
 
111
138
  std::vector<IKS::IK_Solution> Robot::calculate_IK_batched(std::vector<IKS::Homogeneous_T> EE_pose_batch, const unsigned worker_threads) const
112
139
  {
140
+ if (!bot_kinematics->has_known_decomposition())
141
+ {
142
+ throw std::runtime_error(decomposition_unknown_exception_info);
143
+ }
144
+
113
145
  std::vector<IKS::IK_Solution> solutions(EE_pose_batch.size());
114
146
  std::vector<std::thread> thread_pool;
115
147
  thread_pool.reserve(worker_threads);
@@ -231,7 +263,7 @@ namespace EAIK
231
263
 
232
264
  bool Robot::is_spherical() const
233
265
  {
234
- return spherical_wrist;
266
+ return this->bot_kinematics->is_spherical();
235
267
  }
236
268
 
237
269
  bool Robot::has_known_decomposition() const
@@ -26,6 +26,15 @@ namespace EAIK
26
26
 
27
27
  bool is_spherical() const;
28
28
  bool has_known_decomposition() const;
29
+
30
+ Eigen::MatrixXd get_remodeled_H() const;
31
+ Eigen::MatrixXd get_remodeled_P() const;
32
+
33
+ Eigen::MatrixXd get_original_H() const;
34
+ Eigen::MatrixXd get_original_P() const;
35
+
36
+ std::string get_kinematic_family() const;
37
+
29
38
  private:
30
39
  // Init function to allow nice constructor overloading
31
40
  void init(const Eigen::MatrixXd &H, const Eigen::MatrixXd &P, const std::vector<std::pair<int, double>>& fixed_axes={}, bool is_double_precision=true);
@@ -41,6 +50,9 @@ namespace EAIK
41
50
  Eigen::Matrix<double, 3, 3> R6T;
42
51
  Eigen::Matrix<double, 3, 3> R6T_partial;
43
52
  std::vector<std::pair<int, double>> fixed_axes; // Locked axes sorted by rising indices (!)
53
+
54
+ const std::string decomposition_unknown_exception_info{"No Subproblem-Decomposition for the given manipulator is currently known! Analytical IK computation is not possible."};
55
+
44
56
  };
45
57
  } // namespace EAIK
46
58
  #endif
@@ -0,0 +1,48 @@
1
+ #include <eigen3/Eigen/Dense>
2
+ #include <vector>
3
+ #include <iostream>
4
+ #include <math.h>
5
+
6
+ #include "sp.h"
7
+ #include "IKS.h"
8
+ #include "utils/kinematic_utils.h"
9
+
10
+ namespace IKS
11
+ {
12
+ General_1R::General_1R(const Eigen::Matrix<double, 3, 1> &H, const Eigen::Matrix<double, 3, 2> &P)
13
+ : General_Robot(H,P), H(H), P(P)
14
+ {
15
+ }
16
+
17
+ IK_Solution General_1R::calculate_IK(const Homogeneous_T &ee_position_orientation) const
18
+ {
19
+ IK_Solution solution = calculate_position_IK(ee_position_orientation.block<3, 1>(0, 3));
20
+
21
+ // 6DOF Problem for 1R is overconstrained -> "Throw away" extraneous orientation solutions
22
+ return enforce_solution_consistency(solution, ee_position_orientation);
23
+ }
24
+
25
+ IK_Solution General_1R::calculate_position_IK(const Eigen::Vector3d &ee_position) const
26
+ {
27
+ IK_Solution sol;
28
+ const Eigen::Vector3d p_1t = ee_position - this->P.col(0);
29
+ SP1 sp1(this->P.col(1), p_1t, this->H.col(0));
30
+ sp1.solve();
31
+ sol.Q.push_back({sp1.get_theta()});
32
+ sol.is_LS_vec.push_back(sp1.solution_is_ls());
33
+
34
+ return sol;
35
+ }
36
+
37
+ IK_Solution General_1R::calculate_orientation_IK(const Eigen::Matrix3d &ee_orientation) const
38
+ {
39
+ IK_Solution sol;
40
+ const Eigen::Vector3d h_n = create_normal_vector(this->H.col(0));
41
+ SP1 sp1(h_n, ee_orientation*h_n, this->H.col(0));
42
+ sp1.solve();
43
+ sol.Q.push_back({sp1.get_theta()});
44
+ sol.is_LS_vec.push_back(sp1.solution_is_ls());
45
+
46
+ return sol;
47
+ }
48
+ };
@@ -0,0 +1,89 @@
1
+ #include <eigen3/Eigen/Dense>
2
+ #include <vector>
3
+ #include <iostream>
4
+ #include <math.h>
5
+
6
+ #include "sp.h"
7
+ #include "IKS.h"
8
+ #include "utils/kinematic_utils.h"
9
+ #include "kinematic_remodeling.h"
10
+
11
+ namespace IKS
12
+ {
13
+ General_2R::General_2R(const Eigen::Matrix<double, 3, 2> &H, const Eigen::Matrix<double, 3, 3> &P)
14
+ : General_Robot(H, P), H(H), P(P)
15
+ {
16
+ }
17
+
18
+ IK_Solution General_2R::calculate_IK(const Homogeneous_T &ee_position_orientation) const
19
+ {
20
+ IK_Solution solution = calculate_position_IK(ee_position_orientation.block<3, 1>(0, 3));
21
+
22
+ // 6DOF Problem for 2R is overconstrained -> "Throw away" extraneous orientation solutions
23
+ return enforce_solution_consistency(solution, ee_position_orientation);
24
+ }
25
+
26
+ IK_Solution General_2R::calculate_position_IK(const Eigen::Vector3d &ee_position) const
27
+ {
28
+ IK_Solution solution;
29
+ const Eigen::Vector3d p_1ee = ee_position - this->P.col(0);
30
+
31
+ if (EAIK::do_axes_intersect(this->H.col(0), this->H.col(1), this->P.col(1), ZERO_THRESH, ZERO_THRESH))
32
+ {
33
+ // (h1 x h2)(p12)==0) -> h1 intersects h2
34
+ SP2 sp2(p_1ee, this->P.col(2), -this->H.col(0), this->H.col(1));
35
+ sp2.solve();
36
+ const std::vector<double>& theta_1 = sp2.get_theta_1();
37
+ const std::vector<double>& theta_2 = sp2.get_theta_2();
38
+
39
+ for(unsigned i = 0; i < theta_1.size(); i++)
40
+ {
41
+ solution.Q.push_back({theta_1.at(i), theta_2.at(i)});
42
+ solution.is_LS_vec.push_back(sp2.solution_is_ls());
43
+ }
44
+ }
45
+ else
46
+ {
47
+ SP3 sp3(this->P.col(2), -this->P.col(1), this->H.col(1), p_1ee.norm());
48
+ sp3.solve();
49
+
50
+ for (const auto &q2 : sp3.get_theta())
51
+ {
52
+ const Eigen::Matrix3d r_12 = Eigen::AngleAxisd(q2, this->H.col(1).normalized()).toRotationMatrix();
53
+ SP1 sp1(this->P.col(1) + r_12 * this->P.col(2), p_1ee, this->H.col(0));
54
+ sp1.solve();
55
+ solution.Q.push_back({sp1.get_theta(), q2});
56
+ solution.is_LS_vec.push_back(sp1.solution_is_ls() || sp3.solution_is_ls());
57
+ }
58
+ }
59
+
60
+ return enforce_solution_consistency(solution, ee_position);
61
+ }
62
+
63
+ IK_Solution General_2R::calculate_orientation_IK(const Eigen::Matrix3d &ee_orientation) const
64
+ {
65
+ IK_Solution solution;
66
+ if (this->H.col(0).cross(this->H.col(1)).norm() > ZERO_THRESH)
67
+ {
68
+ const Eigen::Vector3d h_n = this->H.col(0).cross(this->H.col(1));
69
+ SP2 sp2(ee_orientation*h_n, h_n, -this->H.col(0), this->H.col(1));
70
+ sp2.solve();
71
+
72
+ const std::vector<double> &theta_1 = sp2.get_theta_1();
73
+ const std::vector<double> &theta_2 = sp2.get_theta_2();
74
+
75
+ for (unsigned i = 0; i < theta_1.size(); i++)
76
+ {
77
+ solution.Q.push_back({theta_1.at(i), theta_2.at(i)});
78
+ solution.is_LS_vec.push_back(sp2.solution_is_ls());
79
+ }
80
+ }
81
+ else
82
+ {
83
+ // Implicit redundancy
84
+ throw new std::runtime_error("Can not calculate orientation IK for implicitly redundant manipulator");
85
+ }
86
+
87
+ return enforce_solution_consistency(solution, ee_orientation);
88
+ }
89
+ };
@@ -97,20 +97,18 @@ namespace IKS
97
97
  }
98
98
  else
99
99
  {
100
- double d = this->H.col(0).transpose()*(p_13-this->P.col(1));
101
- SP4 sp4(this->H.col(0), this->P.col(2), this->H.col(1), d);
102
- sp4.solve();
100
+ SP3 sp3(this->P.col(2), -this->P.col(1), this->H.col(1), p_13.norm());
101
+ sp3.solve();
103
102
 
104
- const std::vector<double> &theta_2 = sp4.get_theta();
103
+ const std::vector<double> &theta_2 = sp3.get_theta();
105
104
 
106
105
  for (const auto &q2 : theta_2)
107
106
  {
108
107
  const Eigen::Matrix3d r12 = Eigen::AngleAxisd(q2, this->H.col(1).normalized()).toRotationMatrix();
109
- SP1 sp1(p_13, this->P.col(1)+r12*this->P.col(2), -this->H.col(0));
108
+ SP1 sp1(p_13, this->P.col(1) + r12*this->P.col(2), -this->H.col(0));
110
109
  sp1.solve();
111
-
112
- solution_t_12.Q.push_back({sp1.get_theta(), q2});
113
- solution_t_12.is_LS_vec.push_back(sp4.solution_is_ls()||sp1.solution_is_ls());
110
+ solution_t_12.Q.push_back({sp1.get_theta(),q2});
111
+ solution_t_12.is_LS_vec.push_back(sp3.solution_is_ls()||sp1.solution_is_ls());
114
112
  }
115
113
  }
116
114