017 gtsam/examples/PlanarSLAMExample.cpp

一个在二维平面的SLAM例子

一、问题定义和include files

/**
 * A simple 2D planar slam example with landmarks
 *  - The robot and landmarks are on a 2 meter grid
 *  - Robot poses are facing along the X axis (horizontal, to the right in 2D)
 *  - The robot moves 2 meters each step
 *  - We have full odometry between poses
 *  - We have bearing and range information for measurements
 *  - Landmarks are 2 meters away from the robot trajectory
 */

// As this is a planar SLAM example, we will use Pose2 variables (x, y, theta) to represent
// the robot positions and Point2 variables (x, y) to represent the landmark coordinates.
#include <gtsam/geometry/Pose2.h>
#include <gtsam/geometry/Point2.h>

// Each variable in the system (poses and landmarks) must be identified with a unique key.
// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1).
// Here we will use Symbols
#include <gtsam/inference/Symbol.h>

// In GTSAM, measurement functions are represented as 'factors'. Several common factors
// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems.
// Here we will use a RangeBearing factor for the range-bearing measurements to identified
// landmarks, and Between factors for the relative motion described by odometry measurements.
// Also, we will initialize the robot at the origin using a Prior factor.
#include <gtsam/slam/BetweenFactor.h>
#include <gtsam/sam/BearingRangeFactor.h>

// When the factors are created, we will add them to a Factor Graph. As the factors we are using
// are nonlinear factors, we will need a Nonlinear Factor Graph.
#include <gtsam/nonlinear/NonlinearFactorGraph.h>

// Finally, once all of the factors have been added to our factor graph, we will want to
// solve/optimize to graph to find the best (Maximum A Posteriori) set of variable values.
// GTSAM includes several nonlinear optimizers to perform this step. Here we will use the
// common Levenberg-Marquardt solver
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>

// Once the optimized values have been calculated, we can also calculate the marginal covariance
// of desired variables
#include <gtsam/nonlinear/Marginals.h>

// The nonlinear solvers within GTSAM are iterative solvers, meaning they linearize the
// nonlinear functions around an initial linearization point, then solve the linear system
// to update the linearization point. This happens repeatedly until the solver converges
// to a consistent set of variable values. This requires us to specify an initial guess
// for each variable, held in a Values container.
#include <gtsam/nonlinear/Values.h>

二、main函数

创建因子图

  // Create a factor graph
  NonlinearFactorGraph graph;

创建keys 三个位姿,两个landmark

  // Create the keys we need for this simple example
  static Symbol x1('x', 1), x2('x', 2), x3('x', 3);
  static Symbol l1('l', 1), l2('l', 2);

添加先验因子

  // Add a prior on pose x1 at the origin. A prior factor consists of a mean and
  // a noise model (covariance matrix)
  Pose2 prior(0.0, 0.0, 0.0);  // prior mean is at origin
  auto priorNoise = noiseModel::Diagonal::Sigmas(
      Vector3(0.3, 0.3, 0.1));            // 30cm std on x,y, 0.1 rad on theta
  graph.addPrior(x1, prior, priorNoise);  // add directly to graph

添加里程计因子和对
landmark的观测(二元因子):方位角和距离测量

  // Add two odometry factors
  Pose2 odometry(2.0, 0.0, 0.0);
  // create a measurement for both factors (the same in this case)
  auto odometryNoise = noiseModel::Diagonal::Sigmas(
      Vector3(0.2, 0.2, 0.1));  // 20cm std on x,y, 0.1 rad on theta
  graph.emplace_shared<BetweenFactor<Pose2> >(x1, x2, odometry, odometryNoise);
  graph.emplace_shared<BetweenFactor<Pose2> >(x2, x3, odometry, odometryNoise);
	
  // Add Range-Bearing measurements to two different landmarks
  // create a noise model for the landmark measurements
  auto measurementNoise = noiseModel::Diagonal::Sigmas(
      Vector2(0.1, 0.2));  // 0.1 rad std on bearing, 20cm on range
  // create the measurement values - indices are (pose id, landmark id)
  Rot2 bearing11 = Rot2::fromDegrees(45), bearing21 = Rot2::fromDegrees(90),
       bearing32 = Rot2::fromDegrees(90);
  double range11 = std::sqrt(4.0 + 4.0), range21 = 2.0, range32 = 2.0;
  // Print
  graph.print("Factor Graph:\n");

创建初始估计值

  // Create (deliberately inaccurate) initial estimate
  Values initialEstimate;
  initialEstimate.insert(x1, Pose2(0.5, 0.0, 0.2));
  initialEstimate.insert(x2, Pose2(2.3, 0.1, -0.2));
  initialEstimate.insert(x3, Pose2(4.1, 0.1, 0.1));
  initialEstimate.insert(l1, Point2(1.8, 2.1));
  initialEstimate.insert(l2, Point2(4.1, 1.8));
  // Print
  initialEstimate.print("Initial Estimate:\n");

优化

  // Optimize using Levenberg-Marquardt optimization. The optimizer
  // accepts an optional set of configuration parameters, controlling
  // things like convergence criteria, the type of linear system solver
  // to use, and the amount of information displayed during optimization.
  // Here we will use the default set of parameters.  See the
  // documentation for the full set of parameters.
  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate);
  Values result = optimizer.optimize();
  result.print("Final Result:\n");

获取协方差

  // Calculate and print marginal covariances for all variables
  Marginals marginals(graph, result);
  print(marginals.marginalCovariance(x1), "x1 covariance");
  print(marginals.marginalCovariance(x2), "x2 covariance");
  print(marginals.marginalCovariance(x3), "x3 covariance");
  print(marginals.marginalCovariance(l1), "l1 covariance");
  print(marginals.marginalCovariance(l2), "l2 covariance");

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值