GTSAM学习::Stereo(1)SteroVOExample

5 篇文章 2 订阅

Stereo(1)SteroVOExample


这是一个3D 双目视觉里程计的例子,机器人在原点启动,向前移动1米,双目观测到3个landmark

已知:

  1. 双目相机内参,基线
  2. 双目观测到的对应的landmark像素坐标

求解:

  1. 相机位姿
  2. landmark的坐标 

头文件

#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/StereoFactor.h>

using namespace std;
using namespace gtsam;

 完整代码


直接看注释就可以理解了

/**
 * @file SteroVOExample.cpp
 * @brief A stereo visual odometry example
 * @date May 25, 2014
 * @author Stephen Camp
 */

/**
 * A 3D stereo visual odometry example
 *  - robot starts at origin
 *  -moves forward 1 meter
 *  -takes stereo readings on three landmarks
 */

#include <gtsam/geometry/Pose3.h>
#include <gtsam/geometry/Cal3_S2Stereo.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/NonlinearEquality.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/StereoFactor.h>

using namespace std;
using namespace gtsam;

int main(int argc, char** argv){

  //create graph object, add first pose at origin with key '1'
  NonlinearFactorGraph graph;
  Pose3 first_pose;
  // 插入起点位姿,作为节点1
  graph.emplace_shared<NonlinearEquality<Pose3> >(1, Pose3());

  //create factor noise model with 3 sigmas of value 1
  const noiseModel::Isotropic::shared_ptr model = noiseModel::Isotropic::Sigma(3,1);
  //create stereo camera calibration object with .2m between cameras
  // 双目内参,基线为0.2m
  const Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(1000, 1000, 0, 320, 240, 0.2));

  //create and add stereo factors between first pose (key value 1) and the three landmarks
  // 创建双目观测到的landmark,默认为 像素点在两个图像上的高度heigh一致,区别只在水平方向
  // 因此StereoPoint2类型构造函数为(uL,uR,v)
  // GenericStereoFactor: 通用双目因子, 构造函数( 双目观测点, 噪声模型, 位姿节点id , landmar的id, 相机内参 )
  graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(520, 480, 440), model, 1, 3, K);
  graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(120, 80, 440), model, 1, 4, K);
  graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(320, 280, 140), model, 1, 5, K);

  //create and add stereo factors between second pose and the three landmarks
  // 第二个位姿的因子
  // GenericStereoFactor: 通用双目因子, 构造函数( 双目观测点, 噪声模型, 位姿节点id , landmar的id, 相机内参 )
  graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(570, 520, 490), model, 2, 3, K);
  graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(70, 20, 490), model, 2, 4, K);
  graph.emplace_shared<GenericStereoFactor<Pose3,Point3> >(StereoPoint2(320, 270, 115), model, 2, 5, K);

  //create Values object to contain initial estimates of camera poses and landmark locations
  Values initial_estimate;

  //create and add iniital estimates
  // 设置初始估计值
  initial_estimate.insert(1, first_pose);
  initial_estimate.insert(2, Pose3(Rot3(), Point3(0.1, -0.1, 1.1)));
  initial_estimate.insert(3, Point3(1, 1, 5));
  initial_estimate.insert(4, Point3(-1, 1, 5));
  initial_estimate.insert(5, Point3(0, -0.5, 5));

  //create Levenberg-Marquardt optimizer for resulting factor graph, optimize
  LevenbergMarquardtOptimizer optimizer(graph, initial_estimate);
  Values result = optimizer.optimize();

  result.print("Final result:\n");

  return 0;
}

 

运行结果

Final result:
Values with 5 values:
Value 1: (N5gtsam5Pose3E) R:
[
 	1 0 0;
    	0 1 0;
    	0 0 1
  ]
[0, 0, 0]';
Value 2: (N5gtsam5Pose3E) R:
[
 	           1  9.16275e-17 -4.12051e-16;
    	-9.16275e-17            1  2.99918e-15;
    	 4.12051e-16 -2.99918e-15            1
  ]
[6.11905e-13, -6.22595e-13, 1]';
Value 3: (N5gtsam6Point3E) [1, 1, 5]'

Value 4: (N5gtsam6Point3E) [-1, 1, 5]'

Value 5: (N5gtsam6Point3E) [-6.43194e-17, -0.5, 5]'

 

 

  • 2
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 2
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值