InverseKinematicsExampleExpressions.cpp 3.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091
  1. /* ----------------------------------------------------------------------------
  2. * GTSAM Copyright 2010, Georgia Tech Research Corporation,
  3. * Atlanta, Georgia 30332-0415
  4. * All Rights Reserved
  5. * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
  6. * See LICENSE for the license information
  7. * -------------------------------------------------------------------------- */
  8. /**
  9. * @file InverseKinematicsExampleExpressions.cpp
  10. * @brief Implement inverse kinematics on a three-link arm using expressions.
  11. * @date April 15, 2019
  12. * @author Frank Dellaert
  13. */
  14. #include <gtsam/geometry/Pose2.h>
  15. #include <gtsam/nonlinear/ExpressionFactorGraph.h>
  16. #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
  17. #include <gtsam/nonlinear/Marginals.h>
  18. #include <gtsam/nonlinear/expressions.h>
  19. #include <gtsam/slam/BetweenFactor.h>
  20. #include <gtsam/slam/expressions.h>
  21. #include <cmath>
  22. using namespace std;
  23. using namespace gtsam;
  24. // Scalar multiplication of a vector, with derivatives.
  25. inline Vector3 scalarMultiply(const double& s, const Vector3& v,
  26. OptionalJacobian<3, 1> Hs,
  27. OptionalJacobian<3, 3> Hv) {
  28. if (Hs) *Hs = v;
  29. if (Hv) *Hv = s * I_3x3;
  30. return s * v;
  31. }
  32. // Expression version of scalar product, using above function.
  33. inline Vector3_ operator*(const Double_& s, const Vector3_& v) {
  34. return Vector3_(&scalarMultiply, s, v);
  35. }
  36. // Expression version of Pose2::Expmap
  37. inline Pose2_ Expmap(const Vector3_& xi) { return Pose2_(&Pose2::Expmap, xi); }
  38. // Main function
  39. int main(int argc, char** argv) {
  40. // Three-link planar manipulator specification.
  41. const double L1 = 3.5, L2 = 3.5, L3 = 2.5; // link lengths
  42. const Pose2 sXt0(0, L1 + L2 + L3, M_PI / 2); // end-effector pose at rest
  43. const Vector3 xi1(0, 0, 1), xi2(L1, 0, 1),
  44. xi3(L1 + L2, 0, 1); // screw axes at rest
  45. // Create Expressions for unknowns
  46. using symbol_shorthand::Q;
  47. Double_ q1(Q(1)), q2(Q(2)), q3(Q(3));
  48. // Forward kinematics expression as product of exponentials
  49. Pose2_ l1Zl1 = Expmap(q1 * Vector3_(xi1));
  50. Pose2_ l2Zl2 = Expmap(q2 * Vector3_(xi2));
  51. Pose2_ l3Zl3 = Expmap(q3 * Vector3_(xi3));
  52. Pose2_ forward = compose(compose(l1Zl1, l2Zl2), compose(l3Zl3, Pose2_(sXt0)));
  53. // Create a factor graph with a a single expression factor.
  54. ExpressionFactorGraph graph;
  55. Pose2 desiredEndEffectorPose(3, 2, 0);
  56. auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  57. graph.addExpressionFactor(forward, desiredEndEffectorPose, model);
  58. // Create initial estimate
  59. Values initial;
  60. initial.insert(Q(1), 0.1);
  61. initial.insert(Q(2), 0.2);
  62. initial.insert(Q(3), 0.3);
  63. initial.print("\nInitial Estimate:\n"); // print
  64. GTSAM_PRINT(forward.value(initial));
  65. // Optimize the initial values using a Levenberg-Marquardt nonlinear optimizer
  66. LevenbergMarquardtParams params;
  67. params.setlambdaInitial(1e6);
  68. LevenbergMarquardtOptimizer optimizer(graph, initial, params);
  69. Values result = optimizer.optimize();
  70. result.print("Final Result:\n");
  71. GTSAM_PRINT(forward.value(result));
  72. return 0;
  73. }