GTSAM学习::Example(4)SelfCalibrationExample

5 篇文章 2 订阅

Example(4)SFMExample


基于VisualSLAMExample,但是标定数据还没有固定,在进行SFM的同时估计标定参数

 引入头文件


1、模拟数据

// For loading the data
#include "SFMdata.h"

2、类型(2D点)

// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
#include <gtsam/geometry/Point2.h>

3、Gtsam标准常用头文件

// Inference and optimization
#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/DoglegOptimizer.h>
#include <gtsam/nonlinear/Values.h>

4、因子类型

// SFM-specific factors
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/GeneralSFMFactor.h> // does calibration !

 5、其他

// Standard headers
#include <vector>

using namespace std;
using namespace gtsam;

 

完整代码


// For loading the data
#include "SFMdata.h"

// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
#include <gtsam/geometry/Point2.h>

// Inference and optimization
#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/DoglegOptimizer.h>
#include <gtsam/nonlinear/Values.h>

// SFM-specific factors
#include <gtsam/slam/PriorFactor.h>
#include <gtsam/slam/GeneralSFMFactor.h> // does calibration !

// Standard headers
#include <vector>

#include "tbb/concurrent_queue.h"

using namespace std;
using namespace gtsam;

/* ************************************************************************* */
int main(int argc, char* argv[]) {

  // Create the set of ground-truth
  // 模拟数据
  vector<Point3> points = createPoints();
  vector<Pose3> poses = createPoses();

  // Create the factor graph
  NonlinearFactorGraph graph;

  // Add a prior on pose x1.
  // 创建第一个位姿,作为先验因子,由noise的大小来决定fix的程度
  noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished()); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
  graph.emplace_shared<PriorFactor<Pose3> >(Symbol('x', 0), poses[0], poseNoise);

  // Simulated measurements from each camera pose, adding them to the factor graph
  // 相机内参
  Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
  // 设置观测噪声
  noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
  // 遍历每一个位姿
  for (size_t i = 0; i < poses.size(); ++i) {
    for (size_t j = 0; j < points.size(); ++j) {
        // 取一个仿真位姿
        SimpleCamera camera(poses[i], K);
        // 将3D点根据仿真位姿投影到图像上得到===>像素坐标(u,v)
        Point2 measurement = camera.project(points[j]);
        // The only real difference with the Visual SLAM example is that here we use a
        // different factor type, that also calculates the Jacobian with respect to calibration
        // 与Visual SLAM example唯一不同的是,这里使用了另外一种因子类型,这个类型同时会计算误差相对于标定内参的雅克比
        graph.emplace_shared<GeneralSFMFactor2<Cal3_S2> >(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), Symbol('K', 0));
    }
  }

  // Add a prior on the position of the first landmark.
  // 添加第一个landmark的位置先验
  noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1);
  graph.emplace_shared<PriorFactor<Point3> >(Symbol('l', 0), points[0], pointNoise); // add directly to graph

  // Add a prior on the calibration.
  // 添加内参的先验
  noiseModel::Diagonal::shared_ptr calNoise = noiseModel::Diagonal::Sigmas((Vector(5) << 500, 500, 0.1, 100, 100).finished());
  graph.emplace_shared<PriorFactor<Cal3_S2> >(Symbol('K', 0), K, calNoise);

  // Create the initial estimate to the solution
  // now including an estimate on the camera calibration parameters
  // 为待估计变量设置初始值
  Values initialEstimate;
  initialEstimate.insert(Symbol('K', 0), Cal3_S2(60.0, 60.0, 0.0, 45.0, 45.0));
  for (size_t i = 0; i < poses.size(); ++i)
    initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20))));
  for (size_t j = 0; j < points.size(); ++j)
    initialEstimate.insert<Point3>(Symbol('l', j), points[j] + Point3(-0.25, 0.20, 0.15));

  /* Optimize the graph and print results */
  Values result = DoglegOptimizer(graph, initialEstimate).optimize();
  result.print("Final results:\n");

  return 0;
}
/* ************************************************************************* */

 运行结果

Final results:
Values with 17 values:
Value K0: (N5gtsam7Cal3_S2E) [
 	          50 -7.50557e-16           50;
    	           0           50           50;
    	           0            0            1
  ]

Value l0: (N5gtsam6Point3E) [10, 10, 10]'

Value l1: (N5gtsam6Point3E) [-10, 10, 10]'

Value l2: (N5gtsam6Point3E) [-10, -10, 10]'

Value l3: (N5gtsam6Point3E) [10, -10, 10]'

Value l4: (N5gtsam6Point3E) [10, 10, -10]'

Value l5: (N5gtsam6Point3E) [-10, 10, -10]'

Value l6: (N5gtsam6Point3E) [-10, -10, -10]'

Value l7: (N5gtsam6Point3E) [10, -10, -10]'

Value x0: (N5gtsam5Pose3E) R:
[
 	 2.34636e-14 -4.65595e-15           -1;
    	           1 -9.40407e-15  2.35536e-14;
    	-9.32019e-15           -1   4.6314e-15
  ]
[30, 1.0409e-16, -3.98526e-19]';
Value x1: (N5gtsam5Pose3E) R:
[
 	   -0.707107 -1.14825e-14    -0.707107;
    	    0.707107 -4.34782e-14    -0.707107;
    	-2.25425e-14           -1  3.88846e-14
  ]
[21.2132, 21.2132, -1.98457e-12]';
Value x2: (N5gtsam5Pose3E) R:
[
 	          -1  2.08805e-14  7.91874e-14;
    	 -7.9168e-14 -1.07125e-13           -1;
    	-2.09323e-14           -1    1.072e-13
  ]
[-2.52093e-12, 30, -7.41177e-12]';
Value x3: (N5gtsam5Pose3E) R:
[
 	   -0.707107  7.60986e-14     0.707107;
    	   -0.707107 -1.23084e-13    -0.707107;
    	 3.31998e-14           -1   1.4084e-13
  ]
[-21.2132, 21.2132, -1.37293e-11]';
Value x4: (N5gtsam5Pose3E) R:
[
 	 -1.4723e-14  4.65295e-14            1;
    	          -1 -2.96254e-14 -1.47532e-14;
    	  2.9718e-14           -1  4.65502e-14
  ]
[-30, 3.95964e-14, -1.37123e-11]';
Value x5: (N5gtsam5Pose3E) R:
[
 	   0.707107 8.86597e-14    0.707107;
    	  -0.707107 6.67495e-14    0.707107;
    	1.56324e-14          -1 1.09858e-13
  ]
[-21.2132, -21.2132, -1.33611e-11]';
Value x6: (N5gtsam5Pose3E) R:
[
 	           1  4.00403e-14  1.18239e-13;
    	-1.18245e-13  6.54871e-14            1;
    	 4.00741e-14           -1  6.54957e-14
  ]
[-3.40809e-12, -30, -6.96142e-12]';
Value x7: (N5gtsam5Pose3E) R:
[
 	   0.707107 1.89146e-15   -0.707107;
    	   0.707107 1.70558e-14    0.707107;
    	1.34958e-14          -1 1.07388e-14
  ]
[21.2132, -21.2132, -1.69848e-12]';

 

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值