LCOV - code coverage report
Current view: top level - src/Kinematics - Kinematics.cpp (source / functions) Hit Total Coverage
Test: HLR Lines: 130 131 99.2 %
Date: 2018-01-15 09:15:47 Functions: 7 7 100.0 %

          Line data    Source code
       1             : #include "Kinematics.hpp"
       2             : 
       3             : #include <iostream>
       4             : 
       5             : namespace HLR
       6             : {
       7             : namespace Kinematics
       8             : {
       9             : using IKSolution = std::pair<std::optional<Matrix<double, 4, 1>>,
      10             :                              std::optional<Matrix<double, 4, 1>>>;
      11             : 
      12      230324 : std::optional<Matrix<double, 3, 4>> Kinematics::forward(
      13             :     Matrix<double, 4, 1> angles)
      14             : {
      15     1151614 :     for (std::size_t i = 0; i < angles.get_m(); ++i)
      16             :     {
      17      921292 :         if (!std::isfinite(angles[i][0]))
      18             :         {
      19           2 :             return std::nullopt;
      20             :         }
      21             :     }
      22             : 
      23             :     // Set theta 3 always be horizontal.
      24      230322 :     angles[3][0] = 90 - angles[1][0] - angles[2][0];
      25             : 
      26      230322 :     if (!Kinematics::angles_within_limits(angles))
      27             :     {
      28       18405 :         return std::nullopt;
      29             :     }
      30             : 
      31             :     // Convert angles to radians.
      32      211917 :     angles *= (pi / 180);
      33             : 
      34             :     /*
      35             :      * keep names short because the formules below are unreadable with long
      36             :      * variable names.
      37             :      * p are the end positions of each link.
      38             :      * a are the thetas in radians
      39             :      * l are the joint lengths
      40             :      */
      41      211917 :     Matrix<double, 3, 4> p;
      42      211917 :     const auto& a = angles;
      43      211917 :     const auto& l = joint_lengths;
      44             : 
      45      211917 :     p[0][0] = 0.0;
      46      211917 :     p[1][0] = 0.0;
      47      211917 :     p[2][0] = 0.0;
      48             : 
      49      211917 :     p[0][1] = p[0][0] + (l[0][0] * std::sin(a[1][0]) * std::cos(a[0][0]));
      50      211917 :     p[1][1] = p[1][0] + (l[0][0] * std::cos(a[1][0]));
      51      211917 :     p[2][1] = p[2][0] + (l[0][0] * std::sin(a[1][0]) * std::sin(a[0][0]));
      52             : 
      53      211917 :     p[0][2] =
      54      211917 :         p[0][1] + (l[1][0] * std::sin(a[1][0] + a[2][0]) * std::cos(a[0][0]));
      55      211917 :     p[1][2] = p[1][1] + (l[1][0] * std::cos(a[1][0] + a[2][0]));
      56      211917 :     p[2][2] =
      57      211917 :         p[2][1] + (l[1][0] * std::sin(a[1][0] + a[2][0]) * std::sin(a[0][0]));
      58             : 
      59      211917 :     p[0][3] = p[0][2] + (l[2][0] * std::cos(a[0][0]));
      60      211917 :     p[1][3] = p[1][2];
      61      211917 :     p[2][3] = p[2][2] + (l[2][0] * std::sin(a[0][0]));
      62             : 
      63      211917 :     return p;
      64             : }
      65             : 
      66          10 : IKSolution Kinematics::jacobian_inverse(Matrix<double, 4, 1> current_angles,
      67             :                                         const Matrix<double, 3, 1>& goal)
      68             : {
      69          10 :     IKSolution solutions;
      70             : 
      71             :     // Check if solution is in worksapce.
      72             :     static const double max_arm_length =
      73             :         joint_lengths[0][0] + joint_lengths[1][0] + joint_lengths[2][0];
      74          10 :     if (max_arm_length - goal.get_magnitude() <= 0)
      75             :     {
      76           3 :         return solutions;
      77             :     }
      78             : 
      79             :     // alias variables to the same names they have in the documentation.
      80           7 :     const auto& g = goal;
      81           7 :     auto new_angles = current_angles;
      82           7 :     double beta = 0.1;
      83             : 
      84           7 :     std::size_t i = 0;
      85           7 :     auto e_opt = forward(new_angles);
      86           7 :     auto e_opt_new = e_opt;
      87           7 :     if (!e_opt.has_value())
      88             :     {
      89           1 :         return solutions;
      90             :     }
      91           6 :     auto e = e_opt.value().template slice<0, 3, 3, 1>();
      92           6 :     auto e_new = e;
      93             : 
      94      460592 :     while ((g - e).get_magnitude() > precision && ++i <= max_iterations)
      95             :     {
      96      230293 :         const auto j_i_opt = compute_jacobian(current_angles).inverse();
      97      230293 :         if (!j_i_opt.has_value())
      98             :         {
      99           0 :             break;
     100             :         }
     101             : 
     102      230293 :         const auto& j_i = j_i_opt.value();
     103      230293 :         const auto d_e = beta * (g - e);
     104      230293 :         const auto d_angle = j_i * d_e;
     105      230293 :         new_angles = current_angles + d_angle.template slice<0, 0, 4, 1>();
     106      230293 :         new_angles[3][0] = (pi / 2.0) - new_angles[1][0] - new_angles[2][0];
     107      230293 :         e_opt_new = forward(new_angles);
     108             : 
     109      248687 :         if (!e_opt_new.has_value())
     110             :         {
     111       18394 :             beta /= 2.0;
     112       18394 :             continue;
     113             :         }
     114             : 
     115      211899 :         e_new = e_opt_new.value().template slice<0, 3, 3, 1>();
     116             : 
     117      211899 :         if ((e_new - e + d_e).get_magnitude() > deviation)
     118             :         {
     119       29664 :             beta /= 2.0;
     120             :         }
     121             :         else
     122             :         {
     123      182235 :             beta *= 1.2;
     124      182235 :             e = e_new;
     125      182235 :             current_angles = new_angles;
     126             :         }
     127             :     }
     128             : 
     129           6 :     if ((g - e).get_magnitude() <= precision)
     130             :     {
     131           3 :         solutions.first = new_angles;
     132             :     }
     133             : 
     134           6 :     return solutions;
     135             : }
     136             : 
     137           9 : IKSolution Kinematics::analytical_inverse(const Matrix<double, 3, 1>& goal)
     138             : {
     139           9 :     IKSolution solutions;
     140             : 
     141             :     // Check if solution is in worksapce.
     142             :     static const double max_arm_length =
     143             :         joint_lengths[0][0] + joint_lengths[1][0] + joint_lengths[2][0];
     144           9 :     if (max_arm_length - goal.get_magnitude() <= 0)
     145             :     {
     146           3 :         return solutions;
     147             :     }
     148             : 
     149           6 :     solutions.first = Matrix<double, 4, 1>();
     150           6 :     solutions.second = Matrix<double, 4, 1>();
     151             : 
     152           6 :     const auto& l = joint_lengths;
     153             : 
     154           6 :     auto& s_1 = solutions.first.value();
     155           6 :     auto& s_2 = solutions.second.value();
     156             : 
     157           6 :     double theta_0 = std::atan2(goal[2][0], goal[0][0]);
     158           6 :     double x = std::hypot(goal[2][0], goal[0][0]) - l[2][0];
     159           6 :     double y = goal[1][0];
     160             : 
     161             :     double cos_theta_2 =
     162           6 :         ((x * x) + (y * y) - (l[0][0] * l[0][0]) - (l[1][0] * l[1][0]))
     163           6 :         / (2 * l[0][0] * l[1][0]);
     164             : 
     165           6 :     s_1[2][0] =
     166           6 :         std::atan2(std::sqrt(1 - cos_theta_2 * cos_theta_2), cos_theta_2);
     167           6 :     s_2[2][0] =
     168           6 :         std::atan2(-std::sqrt(1 - cos_theta_2 * cos_theta_2), cos_theta_2);
     169             : 
     170          12 :     s_1[1][0] = std::atan2(x, y)
     171          12 :                 - std::atan2(l[1][0] * std::sin(s_1[2][0]),
     172          12 :                              l[0][0] + l[1][0] * std::cos(s_1[2][0]));
     173          12 :     s_2[1][0] = std::atan2(x, y)
     174          12 :                 - std::atan2(l[1][0] * std::sin(s_2[2][0]),
     175          12 :                              l[0][0] + l[1][0] * std::cos(s_2[2][0]));
     176             : 
     177           6 :     s_1[3][0] = (pi / 2.0) - s_1[1][0] - s_1[2][0];
     178           6 :     s_2[3][0] = (pi / 2.0) - s_2[1][0] - s_2[2][0];
     179             : 
     180           6 :     s_1[0][0] = theta_0;
     181           6 :     s_2[0][0] = theta_0;
     182             : 
     183           6 :     s_1 *= (180.0 / pi);
     184           6 :     s_2 *= (180.0 / pi);
     185             : 
     186           6 :     const auto fk1 = forward(s_1);
     187           6 :     const auto fk2 = forward(s_2);
     188             : 
     189          12 :     if (!fk1.has_value()
     190           6 :         || (fk1.value().template slice<0, 3, 3, 1>() - goal).get_magnitude()
     191             :                > precision)
     192             :     {
     193           3 :         solutions.first = std::nullopt;
     194             :     }
     195             : 
     196          12 :     if (!fk2.has_value()
     197           6 :         || (fk2.value().template slice<0, 3, 3, 1>() - goal).get_magnitude()
     198             :                > precision)
     199             :     {
     200           6 :         solutions.second = std::nullopt;
     201             :     }
     202             : 
     203           6 :     return solutions;
     204             : }
     205             : 
     206      230293 : Matrix<double, 3, 3> Kinematics::compute_jacobian(
     207             :     const Matrix<double, 4, 1>& current_angles)
     208             : {
     209             :     // alias current angles to a and joint lengths l.
     210      230293 :     auto a = current_angles * (pi / 180);
     211      230293 :     const auto& l = joint_lengths;
     212      230293 :     Matrix<double, 3, 3> jacobian;
     213             : 
     214      230293 :     jacobian[0][0] =
     215      230293 :         (l[0][0] * std::sin(a[1][0]) + l[1][0] * std::sin(a[1][0] + a[2][0]))
     216      230293 :         * -std::sin(a[0][0]);
     217      230293 :     jacobian[0][1] =
     218      230293 :         (l[0][0] * std::cos(a[1][0]) + l[1][0] * std::cos(a[1][0] + a[2][0]))
     219      230293 :         * std::cos(a[0][0]);
     220      230293 :     jacobian[0][2] = l[1][0] * std::cos(a[1][0] + a[2][0]) * std::cos(a[0][0]);
     221             : 
     222      230293 :     jacobian[1][0] = 0;
     223      230293 :     jacobian[1][1] =
     224      230293 :         -l[0][0] * std::sin(a[1][0]) - l[1][0] * std::sin(a[1][0] + a[2][0]);
     225      230293 :     jacobian[1][2] = -l[1][0] * std::sin(a[1][0] + a[2][0]);
     226             : 
     227      230293 :     jacobian[2][0] =
     228      230293 :         (l[0][0] * std::sin(a[1][0]) + l[1][0] * std::sin(a[1][0] + a[2][0]))
     229      230293 :         * std::cos(a[0][0]);
     230      230293 :     jacobian[2][1] =
     231      230293 :         (l[0][0] * std::cos(a[1][0]) + l[1][0] * std::cos(a[1][0] + a[2][0]))
     232      230293 :         * std::sin(a[0][0]);
     233      230293 :     jacobian[2][2] = l[1][0] * std::cos(a[1][0] + a[2][0]) * std::sin(a[0][0]);
     234             : 
     235      230293 :     return jacobian;
     236             : }
     237             : 
     238      230322 : bool Kinematics::angles_within_limits(const Matrix<double, 4, 1>& angles)
     239             : {
     240     1114794 :     for (std::size_t i = 0; i < angles.get_m(); ++i)
     241             :     {
     242     1805754 :         if (servo_limits[i][0] > angles[i][0]
     243      902877 :             || servo_limits[i][1] < angles[i][0])
     244             :         {
     245       18405 :             return false;
     246             :         }
     247             :     }
     248             : 
     249      211917 :     return true;
     250             : }
     251             : 
     252             : } // namespace Kinematics
     253           3 : } // namespace HLR

Generated by: LCOV version 1.12