012 gtsam/examples/InverseKinematicsExampleExpressions.cpp

InverseKinematicsExampleExpressions.cpp

Implement inverse kinematics on a three-link arm using expressions

一、预先定义

向量的标量乘法和其中的导数计算

// Scalar multiplication of a vector, with derivatives.
inline Vector3 scalarMultiply(const double& s, const Vector3& v,
                              OptionalJacobian<3, 1> Hs,
                              OptionalJacobian<3, 3> Hv) {
  if (Hs) *Hs = v;
  if (Hv) *Hv = s * I_3x3;
  return s * v;
}

重载*操作符实现向量的标量乘法

// Expression version of scalar product, using above function.
inline Vector3_ operator*(const Double_& s, const Vector3_& v) {
  return Vector3_(&scalarMultiply, s, v);
}

Exp映射

// Expression version of Pose2::Expmap
inline Pose2_ Expmap(const Vector3_& xi) { return Pose2_(&Pose2::Expmap, xi); }

二、main function

连杆设置

  // Three-link planar manipulator specification.
  const double L1 = 3.5, L2 = 3.5, L3 = 2.5;    // link lengths
  const Pose2 sXt0(0, L1 + L2 + L3, M_PI / 2);  // end-effector pose at rest//静止时末端姿势
  const Vector3 xi1(0, 0, 1), xi2(L1, 0, 1),
      xi3(L1 + L2, 0, 1);  // screw axes at rest //静止螺旋轴
  // Create Expressions for unknowns
  using symbol_shorthand::Q;
  Double_ q1(Q(1)), q2(Q(2)), q3(Q(3));
  // Forward kinematics expression as product of exponentials
  // expression 指数映射结果 前向过程
  Pose2_ l1Zl1 = Expmap(q1 * Vector3_(xi1));
  Pose2_ l2Zl2 = Expmap(q2 * Vector3_(xi2));
  Pose2_ l3Zl3 = Expmap(q3 * Vector3_(xi3));
  Pose2_ forward = compose(compose(l1Zl1, l2Zl2), compose(l3Zl3, Pose2_(sXt0)));

构建因子图

  // Create a factor graph with a a single expression factor.
  ExpressionFactorGraph graph;
  Pose2 desiredEndEffectorPose(3, 2, 0);
  auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1));
  graph.addExpressionFactor(forward, desiredEndEffectorPose, model);
  // Create initial estimate
  Values initial;
  initial.insert(Q(1), 0.1);
  initial.insert(Q(2), 0.2);
  initial.insert(Q(3), 0.3);
  initial.print("\nInitial Estimate:\n");  // print
  GTSAM_PRINT(forward.value(initial));

优化输出结果

  // Optimize the initial values using a Levenberg-Marquardt nonlinear optimizer
  LevenbergMarquardtParams params;
  params.setlambdaInitial(1e6);
  LevenbergMarquardtOptimizer optimizer(graph, initial, params);
  Values result = optimizer.optimize();
  result.print("Final Result:\n");

  GTSAM_PRINT(forward.value(result));

  return 0;
  • 0
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值